diff --git a/nav2_map_server/src/map_io.cpp b/nav2_map_server/src/map_io.cpp index d926c5b07e..b26b09be38 100644 --- a/nav2_map_server/src/map_io.cpp +++ b/nav2_map_server/src/map_io.cpp @@ -60,6 +60,13 @@ char * dirname(char * path) return path; } + /* Replace all "\" with "/" */ + char * c = path; + while (*c != '\0') { + if (*c == '\\') {*c = '/';} + ++c; + } + /* Find last '/'. */ last_slash = path != NULL ? strrchr(path, '/') : NULL; diff --git a/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp b/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp index 58b53fdf8c..a656cf9220 100644 --- a/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp +++ b/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp @@ -17,6 +17,7 @@ #include #include +#undef NO_ERROR #include #include diff --git a/nav2_smac_planner/CMakeLists.txt b/nav2_smac_planner/CMakeLists.txt index 05b84e4f8b..6da37d4c20 100644 --- a/nav2_smac_planner/CMakeLists.txt +++ b/nav2_smac_planner/CMakeLists.txt @@ -30,7 +30,11 @@ endif() set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") -add_compile_options(-O3 -Wextra -Wdeprecated -fPIC) +if(MSVC) + add_compile_definitions(_USE_MATH_DEFINES) +else() + add_compile_options(-O3 -Wextra -Wdeprecated -fPIC) +endif() include_directories( include diff --git a/nav2_smac_planner/src/costmap_downsampler.cpp b/nav2_smac_planner/src/costmap_downsampler.cpp index 32bc05b36a..725ce5f469 100644 --- a/nav2_smac_planner/src/costmap_downsampler.cpp +++ b/nav2_smac_planner/src/costmap_downsampler.cpp @@ -90,8 +90,8 @@ nav2_costmap_2d::Costmap2D * CostmapDownsampler::downsample( } // Assign costs - for (uint i = 0; i < _downsampled_size_x; ++i) { - for (uint j = 0; j < _downsampled_size_y; ++j) { + for (unsigned int i = 0; i < _downsampled_size_x; ++i) { + for (unsigned int j = 0; j < _downsampled_size_y; ++j) { setCostOfCell(i, j); } } @@ -130,12 +130,12 @@ void CostmapDownsampler::setCostOfCell( unsigned int x_offset = new_mx * _downsampling_factor; unsigned int y_offset = new_my * _downsampling_factor; - for (uint i = 0; i < _downsampling_factor; ++i) { + for (unsigned int i = 0; i < _downsampling_factor; ++i) { mx = x_offset + i; if (mx >= _size_x) { continue; } - for (uint j = 0; j < _downsampling_factor; ++j) { + for (unsigned int j = 0; j < _downsampling_factor; ++j) { my = y_offset + j; if (my >= _size_y) { continue; diff --git a/nav2_smac_planner/test/deprecated/smoother.hpp b/nav2_smac_planner/test/deprecated/smoother.hpp index e523eaea1b..91cfcd257c 100644 --- a/nav2_smac_planner/test/deprecated/smoother.hpp +++ b/nav2_smac_planner/test/deprecated/smoother.hpp @@ -105,8 +105,13 @@ class Smoother { _options.max_solver_time_in_seconds = params.max_time; - double parameters[path.size() * 2]; // NOLINT - for (uint i = 0; i != path.size(); i++) { +#ifdef _MSC_VER + std::vector parameters_vec(path.size() * 2); + double * parameters = parameters_vec.data(); +#else + double parameters[path.size() * 2]; // NOLINT +#endif + for (unsigned int i = 0; i != path.size(); i++) { parameters[2 * i] = path[i][0]; parameters[2 * i + 1] = path[i][1]; } @@ -123,7 +128,7 @@ class Smoother return false; } - for (uint i = 0; i != path.size(); i++) { + for (unsigned int i = 0; i != path.size(); i++) { path[i][0] = parameters[2 * i]; path[i][1] = parameters[2 * i + 1]; } diff --git a/nav2_smac_planner/test/deprecated/smoother_cost_function.hpp b/nav2_smac_planner/test/deprecated/smoother_cost_function.hpp index 7e5349c894..acd6414567 100644 --- a/nav2_smac_planner/test/deprecated/smoother_cost_function.hpp +++ b/nav2_smac_planner/test/deprecated/smoother_cost_function.hpp @@ -122,7 +122,7 @@ class UnconstrainedSmootherCostFunction : public ceres::FirstOrderFunction Eigen::Vector2d xi; Eigen::Vector2d xi_p1; Eigen::Vector2d xi_m1; - uint x_index, y_index; + unsigned int x_index, y_index; cost[0] = 0.0; double cost_raw = 0.0; double grad_x_raw = 0.0; diff --git a/nav2_util/src/dump_params.cpp b/nav2_util/src/dump_params.cpp index 1908d65ead..49fb5b0438 100644 --- a/nav2_util/src/dump_params.cpp +++ b/nav2_util/src/dump_params.cpp @@ -12,7 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. +#ifndef _WIN32 #include +#endif #include #include diff --git a/nav2_util/test/test_lifecycle_cli_node.cpp b/nav2_util/test/test_lifecycle_cli_node.cpp index 2177412e7d..50a458cb1f 100644 --- a/nav2_util/test/test_lifecycle_cli_node.cpp +++ b/nav2_util/test/test_lifecycle_cli_node.cpp @@ -23,6 +23,10 @@ #include "nav2_util/node_thread.hpp" #include "rclcpp/rclcpp.hpp" +#ifdef _WIN32 +#include +#endif + class DummyNode : public nav2_util::LifecycleNode { public: @@ -80,7 +84,11 @@ TEST(LifeycleCLI, fails_no_node_name) Handle handle; auto rc = system("ros2 run nav2_util lifecycle_bringup"); (void)rc; +#ifdef _WIN32 + Sleep(1000); +#else sleep(1); +#endif // check node didn't mode EXPECT_EQ(handle.node->activated, false); SUCCEED(); @@ -90,7 +98,11 @@ TEST(LifeycleCLI, succeeds_node_name) { Handle handle; auto rc = system("ros2 run nav2_util lifecycle_bringup nav2_test_cli"); +#ifdef _WIN32 + Sleep(3000); +#else sleep(3); +#endif // check node moved (void)rc; EXPECT_EQ(handle.node->activated, true);