|
| 1 | +diff --git a/CMakeLists.txt b/CMakeLists.txt |
| 2 | +index 5a9fdf1..3d2e2a2 100644 |
| 3 | +--- a/CMakeLists.txt |
| 4 | ++++ b/CMakeLists.txt |
| 5 | +@@ -10,6 +10,8 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") |
| 6 | + add_compile_options(-Wall -Wextra -Wpedantic) |
| 7 | + endif() |
| 8 | + |
| 9 | ++set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) |
| 10 | ++ |
| 11 | + set(CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/cmake") |
| 12 | + |
| 13 | + find_package(ament_cmake_ros REQUIRED) |
| 14 | +@@ -64,6 +66,8 @@ target_link_libraries(ublox_gps PUBLIC |
| 15 | + ublox_serialization::ublox_serialization |
| 16 | + ) |
| 17 | + |
| 18 | ++target_compile_definitions(ublox_gps PRIVATE _USE_MATH_DEFINES) |
| 19 | ++ |
| 20 | + install(TARGETS ublox_gps EXPORT export_${PROJECT_NAME} |
| 21 | + ARCHIVE DESTINATION lib |
| 22 | + LIBRARY DESTINATION lib |
| 23 | +diff --git a/include/ublox_gps/ublox_firmware7plus.hpp b/include/ublox_gps/ublox_firmware7plus.hpp |
| 24 | +index 84ffe7a..1b8043d 100644 |
| 25 | +--- a/include/ublox_gps/ublox_firmware7plus.hpp |
| 26 | ++++ b/include/ublox_gps/ublox_firmware7plus.hpp |
| 27 | +@@ -175,7 +175,17 @@ class UbloxFirmware7Plus : public UbloxFirmware { |
| 28 | + } |
| 29 | + // Raise diagnostic level to error if no fix |
| 30 | + if (last_nav_pvt_.fix_type == ublox_msgs::msg::NavPVT::FIX_TYPE_NO_FIX) { |
| 31 | ++#if defined(_WIN32) |
| 32 | ++# if defined(ERROR) |
| 33 | ++# pragma push_macro("ERROR") |
| 34 | ++# undef ERROR |
| 35 | ++# endif |
| 36 | ++#endif |
| 37 | + stat.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; |
| 38 | ++#if defined(_WIN32) |
| 39 | ++# pragma warning(suppress : 4602) |
| 40 | ++# pragma pop_macro("ERROR") |
| 41 | ++#endif |
| 42 | + stat.message = "No fix"; |
| 43 | + } |
| 44 | + |
| 45 | +diff --git a/src/gps.cpp b/src/gps.cpp |
| 46 | +index e71377d..9e91478 100644 |
| 47 | +--- a/src/gps.cpp |
| 48 | ++++ b/src/gps.cpp |
| 49 | +@@ -138,12 +138,6 @@ void Gps::initializeSerial(const std::string & port, unsigned int baudrate, |
| 50 | + |
| 51 | + RCLCPP_INFO(logger_, "U-Blox: Opened serial port %s", port.c_str()); |
| 52 | + |
| 53 | +- int fd = serial->native_handle(); |
| 54 | +- termios tio{}; |
| 55 | +- tcgetattr(fd, &tio); |
| 56 | +- cfmakeraw(&tio); |
| 57 | +- tcsetattr(fd, TCSANOW, &tio); |
| 58 | +- |
| 59 | + // Set the I/O worker |
| 60 | + if (worker_) { |
| 61 | + return; |
| 62 | +diff --git a/src/hpg_ref_product.cpp b/src/hpg_ref_product.cpp |
| 63 | +index b12caaf..62c61b4 100644 |
| 64 | +--- a/src/hpg_ref_product.cpp |
| 65 | ++++ b/src/hpg_ref_product.cpp |
| 66 | +@@ -224,7 +224,17 @@ void HpgRefProduct::tmode3Diagnostics( |
| 67 | + stat.message = "Disabled"; |
| 68 | + } else if (mode_ == SURVEY_IN) { |
| 69 | + if (!last_nav_svin_.active && !last_nav_svin_.valid) { |
| 70 | ++#if defined(_WIN32) |
| 71 | ++# if defined(ERROR) |
| 72 | ++# pragma push_macro("ERROR") |
| 73 | ++# undef ERROR |
| 74 | ++# endif |
| 75 | ++#endif |
| 76 | + stat.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; |
| 77 | ++#if defined(_WIN32) |
| 78 | ++# pragma warning(suppress : 4602) |
| 79 | ++# pragma pop_macro("ERROR") |
| 80 | ++#endif |
| 81 | + stat.message = "Survey-In inactive and invalid"; |
| 82 | + } else if (last_nav_svin_.active && !last_nav_svin_.valid) { |
| 83 | + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; |
| 84 | +diff --git a/src/hpg_rov_product.cpp b/src/hpg_rov_product.cpp |
| 85 | +index 7b524d5..b08a862 100644 |
| 86 | +--- a/src/hpg_rov_product.cpp |
| 87 | ++++ b/src/hpg_rov_product.cpp |
| 88 | +@@ -65,7 +65,17 @@ void HpgRovProduct::carrierPhaseDiagnostics( |
| 89 | + if (carr_soln & ublox_msgs::msg::NavRELPOSNED::FLAGS_CARR_SOLN_NONE || |
| 90 | + !(last_rel_pos_.flags & ublox_msgs::msg::NavRELPOSNED::FLAGS_DIFF_SOLN && |
| 91 | + last_rel_pos_.flags & ublox_msgs::msg::NavRELPOSNED::FLAGS_REL_POS_VALID)) { |
| 92 | ++#if defined(_WIN32) |
| 93 | ++# if defined(ERROR) |
| 94 | ++# pragma push_macro("ERROR") |
| 95 | ++# undef ERROR |
| 96 | ++# endif |
| 97 | ++#endif |
| 98 | + stat.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; |
| 99 | ++#if defined(_WIN32) |
| 100 | ++# pragma warning(suppress : 4602) |
| 101 | ++# pragma pop_macro("ERROR") |
| 102 | ++#endif |
| 103 | + stat.message = "None"; |
| 104 | + } else { |
| 105 | + if (carr_soln & ublox_msgs::msg::NavRELPOSNED::FLAGS_CARR_SOLN_FLOAT) { |
| 106 | +diff --git a/src/node.cpp b/src/node.cpp |
| 107 | +index 23f5172..0153410 100644 |
| 108 | +--- a/src/node.cpp |
| 109 | ++++ b/src/node.cpp |
| 110 | +@@ -506,7 +506,17 @@ void UbloxNode::pollMessages() { |
| 111 | + } |
| 112 | + |
| 113 | + void UbloxNode::printInf(const ublox_msgs::msg::Inf &m, uint8_t id) { |
| 114 | ++#if defined(_WIN32) |
| 115 | ++# if defined(ERROR) |
| 116 | ++# pragma push_macro("ERROR") |
| 117 | ++# undef ERROR |
| 118 | ++# endif |
| 119 | ++#endif |
| 120 | + if (id == ublox_msgs::Message::INF::ERROR) { |
| 121 | ++#if defined(_WIN32) |
| 122 | ++# pragma warning(suppress : 4602) |
| 123 | ++# pragma pop_macro("ERROR") |
| 124 | ++#endif |
| 125 | + RCLCPP_ERROR(this->get_logger(), "INF: %s", std::string(m.str.begin(), m.str.end()).c_str()); |
| 126 | + } else if (id == ublox_msgs::Message::INF::WARNING) { |
| 127 | + RCLCPP_WARN(this->get_logger(), "INF: %s", std::string(m.str.begin(), m.str.end()).c_str()); |
| 128 | +@@ -546,10 +556,20 @@ void UbloxNode::subscribe() { |
| 129 | + } |
| 130 | + |
| 131 | + if (getRosBoolean(this, "inf.error")) { |
| 132 | ++#if defined(_WIN32) |
| 133 | ++# if defined(ERROR) |
| 134 | ++# pragma push_macro("ERROR") |
| 135 | ++# undef ERROR |
| 136 | ++# endif |
| 137 | ++#endif |
| 138 | + gps_->subscribeId<ublox_msgs::msg::Inf>( |
| 139 | + std::bind(&UbloxNode::printInf, this, std::placeholders::_1, |
| 140 | + ublox_msgs::Message::INF::ERROR), |
| 141 | + ublox_msgs::Message::INF::ERROR); |
| 142 | ++#if defined(_WIN32) |
| 143 | ++# pragma warning(suppress : 4602) |
| 144 | ++# pragma pop_macro("ERROR") |
| 145 | ++#endif |
| 146 | + } |
| 147 | + |
| 148 | + if (getRosBoolean(this, "inf.notice")) { |
| 149 | +@@ -616,8 +636,7 @@ void UbloxNode::processMonVer() { |
| 150 | + RCLCPP_DEBUG(this->get_logger(), "%s", |
| 151 | + std::string(monVer.extension[i].field.begin(), monVer.extension[i].field.end()).c_str()); |
| 152 | + // Find the end of the string (null character) |
| 153 | +- unsigned char* end = std::find(monVer.extension[i].field.begin(), |
| 154 | +- monVer.extension[i].field.end(), '\0'); |
| 155 | ++ auto end = std::find(monVer.extension[i].field.begin(), monVer.extension[i].field.end(), '\0'); |
| 156 | + extensions.emplace_back(std::string(monVer.extension[i].field.begin(), end)); |
| 157 | + } |
| 158 | + |
| 159 | +diff --git a/src/ublox_firmware6.cpp b/src/ublox_firmware6.cpp |
| 160 | +index 0bb7f3b..24046c5 100644 |
| 161 | +--- a/src/ublox_firmware6.cpp |
| 162 | ++++ b/src/ublox_firmware6.cpp |
| 163 | +@@ -151,7 +151,17 @@ void UbloxFirmware6::fixDiagnostic( |
| 164 | + } |
| 165 | + // Raise diagnostic level to error if no fix |
| 166 | + if (last_nav_sol_.gps_fix == ublox_msgs::msg::NavSOL::GPS_NO_FIX) { |
| 167 | ++#if defined(_WIN32) |
| 168 | ++# if defined(ERROR) |
| 169 | ++# pragma push_macro("ERROR") |
| 170 | ++# undef ERROR |
| 171 | ++# endif |
| 172 | ++#endif |
| 173 | + stat.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; |
| 174 | ++#if defined(_WIN32) |
| 175 | ++# pragma warning(suppress : 4602) |
| 176 | ++# pragma pop_macro("ERROR") |
| 177 | ++#endif |
| 178 | + stat.message = "No fix"; |
| 179 | + } |
| 180 | + |
0 commit comments