diff --git a/nav2_amcl/src/pf/CMakeLists.txt b/nav2_amcl/src/pf/CMakeLists.txt index 3b4b2fa5ca1..8dc2ccb5719 100644 --- a/nav2_amcl/src/pf/CMakeLists.txt +++ b/nav2_amcl/src/pf/CMakeLists.txt @@ -15,7 +15,9 @@ target_include_directories(pf_lib PRIVATE ../include) if(HAVE_DRAND48) target_compile_definitions(pf_lib PRIVATE "HAVE_DRAND48") endif() -target_link_libraries(pf_lib m) +if(NOT WIN32) + target_link_libraries(pf_lib m) +endif() install(TARGETS pf_lib diff --git a/nav2_behavior_tree/CMakeLists.txt b/nav2_behavior_tree/CMakeLists.txt index 9a58b70082b..c1d9a032cba 100644 --- a/nav2_behavior_tree/CMakeLists.txt +++ b/nav2_behavior_tree/CMakeLists.txt @@ -20,8 +20,6 @@ find_package(nav2_util REQUIRED) nav2_package() -add_compile_options(-Wno-shadow) # Delete after https://github.com/BehaviorTree/BehaviorTree.CPP/issues/811 is released - include_directories( include ) diff --git a/nav2_constrained_smoother/include/nav2_constrained_smoother/smoother.hpp b/nav2_constrained_smoother/include/nav2_constrained_smoother/smoother.hpp index a0d5dfa115e..f37b40ac3bc 100644 --- a/nav2_constrained_smoother/include/nav2_constrained_smoother/smoother.hpp +++ b/nav2_constrained_smoother/include/nav2_constrained_smoother/smoother.hpp @@ -142,10 +142,10 @@ class Smoother std::vector & optimized) { // Create costmap grid - costmap_grid_ = std::make_shared>( + costmap_grid_ = std::make_shared>( costmap->getCharMap(), 0, costmap->getSizeInCellsY(), 0, costmap->getSizeInCellsX()); - auto costmap_interpolator = std::make_shared>>( - *costmap_grid_); + auto costmap_interpolator = + std::make_shared>>(*costmap_grid_); // Create residual blocks const double cusp_half_length = params.cusp_zone_length / 2; @@ -394,7 +394,7 @@ class Smoother bool debug_; ceres::Solver::Options options_; - std::shared_ptr> costmap_grid_; + std::shared_ptr> costmap_grid_; }; } // namespace nav2_constrained_smoother diff --git a/nav2_constrained_smoother/include/nav2_constrained_smoother/smoother_cost_function.hpp b/nav2_constrained_smoother/include/nav2_constrained_smoother/smoother_cost_function.hpp index 7253119721c..adfae2bc242 100644 --- a/nav2_constrained_smoother/include/nav2_constrained_smoother/smoother_cost_function.hpp +++ b/nav2_constrained_smoother/include/nav2_constrained_smoother/smoother_cost_function.hpp @@ -57,7 +57,8 @@ class SmootherCostFunction double next_to_last_length_ratio, bool reversing, const nav2_costmap_2d::Costmap2D * costmap, - const std::shared_ptr>> & costmap_interpolator, + const std::shared_ptr>> & + costmap_interpolator, const SmootherParams & params, double costmap_weight) : original_pos_(original_pos), @@ -244,7 +245,7 @@ class SmootherCostFunction double costmap_weight_; Eigen::Vector2d costmap_origin_; double costmap_resolution_; - std::shared_ptr>> costmap_interpolator_; + std::shared_ptr>> costmap_interpolator_; }; } // namespace nav2_constrained_smoother diff --git a/nav2_constrained_smoother/test/test_smoother_cost_function.cpp b/nav2_constrained_smoother/test/test_smoother_cost_function.cpp index 104b949c4be..24904ef5c55 100644 --- a/nav2_constrained_smoother/test/test_smoother_cost_function.cpp +++ b/nav2_constrained_smoother/test/test_smoother_cost_function.cpp @@ -33,7 +33,8 @@ class TestableSmootherCostFunction : nav2_constrained_smoother::SmootherCostFunc double next_to_last_length_ratio, bool reversing, const nav2_costmap_2d::Costmap2D * costmap, - const std::shared_ptr>> & costmap_interpolator, + const std::shared_ptr>> & + costmap_interpolator, const nav2_constrained_smoother::SmootherParams & params, double costmap_weight) : SmootherCostFunction( @@ -68,7 +69,7 @@ TEST_F(Test, testingCurvatureResidual) nav2_costmap_2d::Costmap2D costmap; TestableSmootherCostFunction fn( Eigen::Vector2d(1.0, 0.0), 1.0, false, - &costmap, std::shared_ptr>>(), + &costmap, std::shared_ptr>>(), nav2_constrained_smoother::SmootherParams(), 0.0 ); @@ -81,7 +82,7 @@ TEST_F(Test, testingCurvatureResidual) params_no_min_turning_radius.max_curvature = 1.0f / 0.0; TestableSmootherCostFunction fn_no_min_turning_radius( Eigen::Vector2d(1.0, 0.0), 1.0, false, - &costmap, std::shared_ptr>>(), + &costmap, std::shared_ptr>>(), params_no_min_turning_radius, 0.0 ); EXPECT_EQ(fn_no_min_turning_radius.getCurvatureResidual(1.0, pt, pt_other, pt_other), 0.0); diff --git a/nav2_docking/opennav_docking/CMakeLists.txt b/nav2_docking/opennav_docking/CMakeLists.txt index 9278234d996..77360c13732 100644 --- a/nav2_docking/opennav_docking/CMakeLists.txt +++ b/nav2_docking/opennav_docking/CMakeLists.txt @@ -25,7 +25,11 @@ find_package(opennav_docking_core REQUIRED) # potentially replace with nav2_common, nav2_package() set(CMAKE_CXX_STANDARD 17) -add_compile_options(-Wall -Wextra -Wpedantic -Werror -Wdeprecated -fPIC -Wshadow -Wnull-dereference) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Werror -Wdeprecated -fPIC -Wshadow -Wnull-dereference) +endif() +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) include_directories( include diff --git a/nav2_docking/opennav_docking_bt/CMakeLists.txt b/nav2_docking/opennav_docking_bt/CMakeLists.txt index c89330ee38a..72c3e7c5ebf 100644 --- a/nav2_docking/opennav_docking_bt/CMakeLists.txt +++ b/nav2_docking/opennav_docking_bt/CMakeLists.txt @@ -15,7 +15,10 @@ find_package(behaviortree_cpp REQUIRED) # potentially replace with nav2_common, nav2_package() set(CMAKE_CXX_STANDARD 17) -add_compile_options(-Wall -Wextra -Wpedantic -Werror -Wdeprecated -fPIC -Wshadow -Wnull-dereference) +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Werror -Wdeprecated -fPIC -Wshadow -Wnull-dereference) +endif() +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) include_directories( include diff --git a/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp b/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp index e2dd85d15b1..499b8c27cf4 100644 --- a/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp +++ b/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp @@ -105,7 +105,7 @@ TEST(ObstacleFootprint, GetOrientedFootprint) pose.theta = theta; footprint_after = dwb_critics::getOrientedFootprint(pose, footprint_before); - for (uint i = 0; i < footprint_before.size(); i++) { + for (unsigned int i = 0; i < footprint_before.size(); i++) { ASSERT_EQ(rotate_origin(footprint_before[i], theta), footprint_after[i]); } diff --git a/nav2_map_server/src/map_io.cpp b/nav2_map_server/src/map_io.cpp index c713e01fe03..e0b0684684c 100644 --- a/nav2_map_server/src/map_io.cpp +++ b/nav2_map_server/src/map_io.cpp @@ -90,7 +90,7 @@ char * dirname(char * path) /* This assignment is ill-designed but the XPG specs require to return a string containing "." in any case no directory part is found and so a static and constant string is required. */ - path = reinterpret_cast(dot); + path = const_cast(dot); } return path; diff --git a/nav2_map_server/test/unit/test_map_io.cpp b/nav2_map_server/test/unit/test_map_io.cpp index 31269cf2d47..28cc0ced5b5 100644 --- a/nav2_map_server/test/unit/test_map_io.cpp +++ b/nav2_map_server/test/unit/test_map_io.cpp @@ -117,7 +117,7 @@ TEST_F(MapIOTester, loadSaveValidPGM) { // 1. Load reference map file and verify obtained OccupancyGrid LoadParameters loadParameters; - fillLoadParameters(path(TEST_DIR) / path(g_valid_pgm_file), loadParameters); + fillLoadParameters(path(TEST_DIR) / path(g_valid_pgm_file).string(), loadParameters); nav_msgs::msg::OccupancyGrid map_msg; ASSERT_NO_THROW(loadMapFromFile(loadParameters, map_msg)); diff --git a/nav2_mppi_controller/CMakeLists.txt b/nav2_mppi_controller/CMakeLists.txt index 95eabf6c411..fca243f0760 100644 --- a/nav2_mppi_controller/CMakeLists.txt +++ b/nav2_mppi_controller/CMakeLists.txt @@ -52,7 +52,7 @@ if(COMPILER_SUPPORTS_AVX512) add_compile_options(-mno-avx512f) endif() -if(COMPILER_SUPPORTS_SSE4) +if(COMPILER_SUPPORTS_SSE4 AND NOT APPLE) add_compile_options(-msse4.2) endif() @@ -94,7 +94,9 @@ add_library(mppi_critics SHARED set(libraries mppi_controller mppi_critics) foreach(lib IN LISTS libraries) - target_compile_options(${lib} PUBLIC -fconcepts) + if(NOT APPLE) + target_compile_options(${lib} PUBLIC -fconcepts) + endif() target_include_directories(${lib} PUBLIC ${xsimd_INCLUDE_DIRS}) # ${OpenMP_INCLUDE_DIRS} target_link_libraries(${lib} xtensor xtensor::optimize xtensor::use_xsimd) ament_target_dependencies(${lib} ${dependencies_pkgs}) diff --git a/nav2_msgs/CMakeLists.txt b/nav2_msgs/CMakeLists.txt index 9efd3f5c15b..77768397a26 100644 --- a/nav2_msgs/CMakeLists.txt +++ b/nav2_msgs/CMakeLists.txt @@ -13,8 +13,10 @@ find_package(action_msgs REQUIRED) nav2_package() -# TODO(jwallace42): This is a work around for https://github.com/ros2/rosidl_typesupport_fastrtps/issues/28 -add_compile_options(-Wno-error=deprecated) +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + # TODO(jwallace42): This is a work around for https://github.com/ros2/rosidl_typesupport_fastrtps/issues/28 + add_compile_options(-Wno-error=deprecated) +endif() rosidl_generate_interfaces(${PROJECT_NAME} "msg/CollisionMonitorState.msg" diff --git a/nav2_regulated_pure_pursuit_controller/test/test_regulated_pp.cpp b/nav2_regulated_pure_pursuit_controller/test/test_regulated_pp.cpp index f5822b0bacc..16cce1bef62 100644 --- a/nav2_regulated_pure_pursuit_controller/test/test_regulated_pp.cpp +++ b/nav2_regulated_pure_pursuit_controller/test/test_regulated_pp.cpp @@ -489,7 +489,7 @@ TEST(RegulatedPurePursuitTest, lookaheadAPI) double dist = 1.0; nav_msgs::msg::Path path; path.poses.resize(10); - for (uint i = 0; i != path.poses.size(); i++) { + for (unsigned int i = 0; i != path.poses.size(); i++) { path.poses[i].pose.position.x = static_cast(i); } diff --git a/nav2_rviz_plugins/include/nav2_rviz_plugins/costmap_cost_tool.hpp b/nav2_rviz_plugins/include/nav2_rviz_plugins/costmap_cost_tool.hpp index 197fe2b6550..3d249f5625f 100644 --- a/nav2_rviz_plugins/include/nav2_rviz_plugins/costmap_cost_tool.hpp +++ b/nav2_rviz_plugins/include/nav2_rviz_plugins/costmap_cost_tool.hpp @@ -17,7 +17,8 @@ #include #include -#include +#include +#include #include namespace nav2_rviz_plugins @@ -42,7 +43,6 @@ class CostmapCostTool : public rviz_common::Tool void handleGlobalCostResponse(rclcpp::Client::SharedFuture); private Q_SLOTS: - void updateAutoDeactivate(); private: rclcpp::Client::SharedPtr local_cost_client_; diff --git a/nav2_rviz_plugins/include/nav2_rviz_plugins/docking_panel.hpp b/nav2_rviz_plugins/include/nav2_rviz_plugins/docking_panel.hpp index fe4acfff350..69656e92399 100644 --- a/nav2_rviz_plugins/include/nav2_rviz_plugins/docking_panel.hpp +++ b/nav2_rviz_plugins/include/nav2_rviz_plugins/docking_panel.hpp @@ -55,7 +55,6 @@ class DockingPanel : public rviz_common::Panel private Q_SLOTS: void startThread(); - void onStartup(); void onDockingButtonPressed(); void onUndockingButtonPressed(); void onCancelDocking(); diff --git a/nav2_rviz_plugins/include/nav2_rviz_plugins/goal_tool.hpp b/nav2_rviz_plugins/include/nav2_rviz_plugins/goal_tool.hpp index 8451fe52941..0d94b8c7f00 100644 --- a/nav2_rviz_plugins/include/nav2_rviz_plugins/goal_tool.hpp +++ b/nav2_rviz_plugins/include/nav2_rviz_plugins/goal_tool.hpp @@ -20,7 +20,6 @@ #include #include "rviz_default_plugins/tools/pose/pose_tool.hpp" -#include "rviz_default_plugins/visibility_control.hpp" namespace rviz_common { @@ -36,7 +35,7 @@ class StringProperty; namespace nav2_rviz_plugins { -class RVIZ_DEFAULT_PLUGINS_PUBLIC GoalTool : public rviz_default_plugins::tools::PoseTool +class GoalTool : public rviz_default_plugins::tools::PoseTool { Q_OBJECT diff --git a/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp b/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp index f9abeea302a..2e7a6f092c7 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp @@ -28,7 +28,6 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_core/planner_exceptions.hpp" -#include "nav2_smac_planner/thirdparty/robin_hood.h" #include "nav2_smac_planner/analytic_expansion.hpp" #include "nav2_smac_planner/node_2d.hpp" #include "nav2_smac_planner/node_hybrid.hpp" @@ -37,6 +36,13 @@ #include "nav2_smac_planner/types.hpp" #include "nav2_smac_planner/constants.hpp" +#ifdef _MSC_VER + #define SELECTED_UNORDERED_MAP std::unordered_map +#else + #include "nav2_smac_planner/thirdparty/robin_hood.h" + #define SELECTED_UNORDERED_MAP robin_hood::unordered_node_map +#endif + namespace nav2_smac_planner { @@ -49,7 +55,7 @@ class AStarAlgorithm { public: typedef NodeT * NodePtr; - typedef robin_hood::unordered_node_map Graph; + typedef SELECTED_UNORDERED_MAP Graph; typedef std::vector NodeVector; typedef std::pair> NodeElement; typedef typename NodeT::Coordinates Coordinates; diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp index 957cdb4cc31..b02266025fc 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp @@ -234,7 +234,7 @@ class Node2D * @brief Initialize the neighborhood to be used in A* * We support 4-connect (VON_NEUMANN) and 8-connect (MOORE) * @param neighborhood The desired neighborhood type - * @param x_size_uint The total x size to find neighbors + * @param x_size_unsigned int The total x size to find neighbors * @param y_size The total y size to find neighbors * @param num_angle_quantization Number of quantizations, must be 0 * @param search_info Search parameters, unused by 2D node diff --git a/nav2_smac_planner/test/deprecated/upsampler.hpp b/nav2_smac_planner/test/deprecated/upsampler.hpp index 90e0f8b4642..375c2492448 100644 --- a/nav2_smac_planner/test/deprecated/upsampler.hpp +++ b/nav2_smac_planner/test/deprecated/upsampler.hpp @@ -158,7 +158,7 @@ class Upsampler // } // std::unique_ptr problem = std::make_unique(); - // for (uint i = 1; i != path_double_sampled.size() - 1; i++) { + // for (unsigned int i = 1; i != path_double_sampled.size() - 1; i++) { // ceres::CostFunction * cost_fn = // new UpsamplerConstrainedCostFunction(path_double_sampled, params, 2, i); // problem->AddResidualBlock( @@ -178,7 +178,7 @@ class Upsampler // } // std::unique_ptr problem2 = std::make_unique(); - // for (uint i = 1; i != path_quad_sampled.size() - 1; i++) { + // for (unsigned int i = 1; i != path_quad_sampled.size() - 1; i++) { // ceres::CostFunction * cost_fn = // new UpsamplerConstrainedCostFunction(path_quad_sampled, params, 4, i); // problem2->AddResidualBlock( diff --git a/nav2_smac_planner/test/deprecated/upsampler_cost_function.hpp b/nav2_smac_planner/test/deprecated/upsampler_cost_function.hpp index 4a89800b5b5..46e178df694 100644 --- a/nav2_smac_planner/test/deprecated/upsampler_cost_function.hpp +++ b/nav2_smac_planner/test/deprecated/upsampler_cost_function.hpp @@ -104,7 +104,7 @@ class UpsamplerCostFunction : 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_smoother/test/test_savitzky_golay_smoother.cpp b/nav2_smoother/test/test_savitzky_golay_smoother.cpp index 524ba4f9fca..d9cdaacb119 100644 --- a/nav2_smoother/test/test_savitzky_golay_smoother.cpp +++ b/nav2_smoother/test/test_savitzky_golay_smoother.cpp @@ -100,7 +100,7 @@ TEST(SmootherTest, test_sg_smoother_basics) straight_regular_path_baseline = straight_regular_path; EXPECT_TRUE(smoother->smooth(straight_regular_path, max_time)); - for (uint i = 0; i != straight_regular_path.poses.size() - 1; i++) { + for (unsigned int i = 0; i != straight_regular_path.poses.size() - 1; i++) { // Check distances are still the same EXPECT_NEAR( fabs( diff --git a/nav2_smoother/test/test_simple_smoother.cpp b/nav2_smoother/test/test_simple_smoother.cpp index 6c845bfb6c6..a1d6539eae8 100644 --- a/nav2_smoother/test/test_simple_smoother.cpp +++ b/nav2_smoother/test/test_simple_smoother.cpp @@ -119,7 +119,7 @@ TEST(SmootherTest, test_simple_smoother) rclcpp::Duration max_time = rclcpp::Duration::from_seconds(1); // 1 second EXPECT_THROW(smoother->smooth(straight_irregular_path, no_time), nav2_core::SmootherTimedOut); EXPECT_TRUE(smoother->smooth(straight_irregular_path, max_time)); - for (uint i = 0; i != straight_irregular_path.poses.size() - 1; i++) { + for (unsigned int i = 0; i != straight_irregular_path.poses.size() - 1; i++) { // Check distances are more evenly spaced out now EXPECT_LT( fabs( @@ -155,7 +155,7 @@ TEST(SmootherTest, test_simple_smoother) straight_regular_path.poses[10].pose.position.y = 1.0; EXPECT_TRUE(smoother->smooth(straight_regular_path, max_time)); - for (uint i = 0; i != straight_regular_path.poses.size() - 1; i++) { + for (unsigned int i = 0; i != straight_regular_path.poses.size() - 1; i++) { // Check distances are still very evenly spaced EXPECT_NEAR( fabs( diff --git a/nav2_util/include/nav2_util/costmap.hpp b/nav2_util/include/nav2_util/costmap.hpp index 0d868df6e03..c02fe32ad66 100644 --- a/nav2_util/include/nav2_util/costmap.hpp +++ b/nav2_util/include/nav2_util/costmap.hpp @@ -113,7 +113,7 @@ class Costmap /** * @brief Get the interpreted value in the costmap - * @return uint value + * @return unsigned int value */ uint8_t interpret_value(const int8_t value) const; diff --git a/nav2_util/src/node_utils.cpp b/nav2_util/src/node_utils.cpp index 993eaf53b6e..3a3efd9db84 100644 --- a/nav2_util/src/node_utils.cpp +++ b/nav2_util/src/node_utils.cpp @@ -92,6 +92,14 @@ rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix) void setSoftRealTimePriority() { + #if defined(__APPLE__) || defined(_WIN32) + std::string errmsg( + "Setting priority as real-time thread is currently only supported on Linux." + "Contributions welcome."); + throw std::runtime_error(errmsg + std::strerror(errno)); + + #else + sched_param sch; sch.sched_priority = 49; if (sched_setscheduler(0, SCHED_FIFO, &sch) == -1) { @@ -101,6 +109,7 @@ void setSoftRealTimePriority() "realtime prioritization! Error: "); throw std::runtime_error(errmsg + std::strerror(errno)); } + #endif } } // namespace nav2_util diff --git a/nav2_velocity_smoother/test/test_velocity_smoother.cpp b/nav2_velocity_smoother/test/test_velocity_smoother.cpp index 76c5e0498b6..947ad54e32a 100644 --- a/nav2_velocity_smoother/test/test_velocity_smoother.cpp +++ b/nav2_velocity_smoother/test/test_velocity_smoother.cpp @@ -278,7 +278,7 @@ TEST(VelocitySmootherTest, testapplyConstraintsPositiveToPositiveAccel) double decel = -1.0; double dv_accel = accel / 20.0; double init_vel, target_vel, v_curr; - uint steps_to_target; + unsigned int steps_to_target; init_vel = 1.0; target_vel = 2.0; @@ -306,7 +306,7 @@ TEST(VelocitySmootherTest, testapplyConstraintsZeroToPositiveAccel) double decel = -1.0; double dv_accel = accel / 20.0; double init_vel, target_vel, v_curr; - uint steps_to_target; + unsigned int steps_to_target; init_vel = 0.0; target_vel = 2.0; @@ -335,7 +335,7 @@ TEST(VelocitySmootherTest, testapplyConstraintsNegativeToPositiveDecelAccel) double dv_accel = accel / 20.0; double dv_decel = -decel / 20.0; double init_vel, target_vel, v_curr; - uint steps_below_zero, steps_above_zero; + unsigned int steps_below_zero, steps_above_zero; init_vel = -1.0; target_vel = 2.0; @@ -368,7 +368,7 @@ TEST(VelocitySmootherTest, testapplyConstraintsNegativeToNegativeAccel) double decel = -1.0; double dv_accel = accel / 20.0; double init_vel, target_vel, v_curr; - uint steps_to_target; + unsigned int steps_to_target; init_vel = -1.0; target_vel = -2.0; @@ -396,7 +396,7 @@ TEST(VelocitySmootherTest, testapplyConstraintsZeroToNegativeAccel) double decel = -1.0; double dv_accel = accel / 20.0; double init_vel, target_vel, v_curr; - uint steps_to_target; + unsigned int steps_to_target; init_vel = 0.0; target_vel = -2.0; @@ -425,7 +425,7 @@ TEST(VelocitySmootherTest, testapplyConstraintsPositiveToNegativeDecelAccel) double dv_accel = accel / 20.0; double dv_decel = -decel / 20.0; double init_vel, target_vel, v_curr; - uint steps_below_zero, steps_above_zero; + unsigned int steps_below_zero, steps_above_zero; init_vel = 1.0; target_vel = -2.0; @@ -460,7 +460,7 @@ TEST(VelocitySmootherTest, testapplyConstraintsPositiveToPositiveDecel) double decel = -1.0; double dv_decel = -decel / 20.0; double init_vel, target_vel, v_curr; - uint steps_to_target; + unsigned int steps_to_target; init_vel = 2.0; target_vel = 1.0; @@ -488,7 +488,7 @@ TEST(VelocitySmootherTest, testapplyConstraintsPositiveToZeroDecel) double decel = -1.0; double dv_decel = -decel / 20.0; double init_vel, target_vel, v_curr; - uint steps_to_target; + unsigned int steps_to_target; init_vel = 2.0; target_vel = 0.0; @@ -516,7 +516,7 @@ TEST(VelocitySmootherTest, testapplyConstraintsNegativeToNegativeDecel) double decel = -1.0; double dv_decel = -decel / 20.0; double init_vel, target_vel, v_curr; - uint steps_to_target; + unsigned int steps_to_target; init_vel = -2.0; target_vel = -1.0; @@ -544,7 +544,7 @@ TEST(VelocitySmootherTest, testapplyConstraintsNegativeToZeroDecel) double decel = -1.0; double dv_decel = -decel / 20.0; double init_vel, target_vel, v_curr; - uint steps_to_target; + unsigned int steps_to_target; init_vel = -2.0; target_vel = 0.0; diff --git a/nav2_waypoint_follower/plugins/photo_at_waypoint.cpp b/nav2_waypoint_follower/plugins/photo_at_waypoint.cpp index 296f8f41de0..4e2858f655c 100644 --- a/nav2_waypoint_follower/plugins/photo_at_waypoint.cpp +++ b/nav2_waypoint_follower/plugins/photo_at_waypoint.cpp @@ -119,7 +119,7 @@ bool PhotoAtWaypoint::processAtWaypoint( std::lock_guard guard(global_mutex_); cv::Mat curr_frame_mat; deepCopyMsg2Mat(curr_frame_msg_, curr_frame_mat); - cv::imwrite(full_path_image_path.c_str(), curr_frame_mat); + cv::imwrite(full_path_image_path.string().c_str(), curr_frame_mat); RCLCPP_INFO( logger_, "Photo has been taken sucessfully at waypoint %i", curr_waypoint_index);