Skip to content

Windows fixes from robostack #5333

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 16 commits into
base: jazzy
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion nav2_amcl/src/pf/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 0 additions & 2 deletions nav2_behavior_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -142,10 +142,10 @@ class Smoother
std::vector<bool> & optimized)
{
// Create costmap grid
costmap_grid_ = std::make_shared<ceres::Grid2D<u_char>>(
costmap_grid_ = std::make_shared<ceres::Grid2D<unsigned char>>(
costmap->getCharMap(), 0, costmap->getSizeInCellsY(), 0, costmap->getSizeInCellsX());
auto costmap_interpolator = std::make_shared<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>>(
*costmap_grid_);
auto costmap_interpolator =
std::make_shared<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>>(*costmap_grid_);

// Create residual blocks
const double cusp_half_length = params.cusp_zone_length / 2;
Expand Down Expand Up @@ -394,7 +394,7 @@ class Smoother

bool debug_;
ceres::Solver::Options options_;
std::shared_ptr<ceres::Grid2D<u_char>> costmap_grid_;
std::shared_ptr<ceres::Grid2D<unsigned char>> costmap_grid_;
};

} // namespace nav2_constrained_smoother
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,8 @@ class SmootherCostFunction
double next_to_last_length_ratio,
bool reversing,
const nav2_costmap_2d::Costmap2D * costmap,
const std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>> & costmap_interpolator,
const std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>> &
costmap_interpolator,
const SmootherParams & params,
double costmap_weight)
: original_pos_(original_pos),
Expand Down Expand Up @@ -244,7 +245,7 @@ class SmootherCostFunction
double costmap_weight_;
Eigen::Vector2d costmap_origin_;
double costmap_resolution_;
std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>> costmap_interpolator_;
std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>> costmap_interpolator_;
};

} // namespace nav2_constrained_smoother
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>> & costmap_interpolator,
const std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>> &
costmap_interpolator,
const nav2_constrained_smoother::SmootherParams & params,
double costmap_weight)
: SmootherCostFunction(
Expand Down Expand Up @@ -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<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>>(),
&costmap, std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>>(),
nav2_constrained_smoother::SmootherParams(), 0.0
);

Expand All @@ -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<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>>(),
&costmap, std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>>(),
params_no_min_turning_radius, 0.0
);
EXPECT_EQ(fn_no_min_turning_radius.getCurvatureResidual(1.0, pt, pt_other, pt_other), 0.0);
Expand Down
6 changes: 5 additions & 1 deletion nav2_docking/opennav_docking/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
5 changes: 4 additions & 1 deletion nav2_docking/opennav_docking_bt/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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]);
}

Expand Down
2 changes: 1 addition & 1 deletion nav2_map_server/src/map_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<char *>(dot);
path = const_cast<char *>(dot);
}

return path;
Expand Down
2 changes: 1 addition & 1 deletion nav2_map_server/test/unit/test_map_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down
6 changes: 4 additions & 2 deletions nav2_mppi_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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()

Expand Down Expand Up @@ -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})
Expand Down
6 changes: 4 additions & 2 deletions nav2_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<double>(i);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,8 @@

#include <nav2_msgs/srv/get_cost.hpp>
#include <rviz_common/tool.hpp>
#include <rviz_default_plugins/tools/point/point_tool.hpp>
#include <rviz_common/properties/bool_property.hpp>
#include <rviz_common/properties/qos_profile_property.hpp>
#include <rclcpp/rclcpp.hpp>

namespace nav2_rviz_plugins
Expand All @@ -42,7 +43,6 @@ class CostmapCostTool : public rviz_common::Tool
void handleGlobalCostResponse(rclcpp::Client<nav2_msgs::srv::GetCost>::SharedFuture);

private Q_SLOTS:
void updateAutoDeactivate();

private:
rclcpp::Client<nav2_msgs::srv::GetCost>::SharedPtr local_cost_client_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,6 @@ class DockingPanel : public rviz_common::Panel

private Q_SLOTS:
void startThread();
void onStartup();
void onDockingButtonPressed();
void onUndockingButtonPressed();
void onCancelDocking();
Expand Down
3 changes: 1 addition & 2 deletions nav2_rviz_plugins/include/nav2_rviz_plugins/goal_tool.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include <memory>

#include "rviz_default_plugins/tools/pose/pose_tool.hpp"
#include "rviz_default_plugins/visibility_control.hpp"

namespace rviz_common
{
Expand All @@ -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

Expand Down
10 changes: 8 additions & 2 deletions nav2_smac_planner/include/nav2_smac_planner/a_star.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand All @@ -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
Copy link
Member

@SteveMacenski SteveMacenski Jul 11, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is significantly slower than the robin hood hashing that we use in the thirdparty directory. Would a major reduction in performance for windows users really be preferable? I think the print out you showed is mostly warnings which can probably be silenced. We have it in the Nav2 codebase so that can be modified and resolved, no?

#else
#include "nav2_smac_planner/thirdparty/robin_hood.h"
#define SELECTED_UNORDERED_MAP robin_hood::unordered_node_map
#endif

namespace nav2_smac_planner
{

Expand All @@ -49,7 +55,7 @@ class AStarAlgorithm
{
public:
typedef NodeT * NodePtr;
typedef robin_hood::unordered_node_map<uint64_t, NodeT> Graph;
typedef SELECTED_UNORDERED_MAP<uint64_t, NodeT> Graph;
typedef std::vector<NodePtr> NodeVector;
typedef std::pair<float, NodeBasic<NodeT>> NodeElement;
typedef typename NodeT::Coordinates Coordinates;
Expand Down
2 changes: 1 addition & 1 deletion nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions nav2_smac_planner/test/deprecated/upsampler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ class Upsampler
// }

// std::unique_ptr<ceres::Problem> problem = std::make_unique<ceres::Problem>();
// 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(
Expand All @@ -178,7 +178,7 @@ class Upsampler
// }

// std::unique_ptr<ceres::Problem> problem2 = std::make_unique<ceres::Problem>();
// 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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion nav2_smoother/test/test_savitzky_golay_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down
4 changes: 2 additions & 2 deletions nav2_smoother/test/test_simple_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down Expand Up @@ -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(
Expand Down
2 changes: 1 addition & 1 deletion nav2_util/include/nav2_util/costmap.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
9 changes: 9 additions & 0 deletions nav2_util/src/node_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand All @@ -101,6 +109,7 @@ void setSoftRealTimePriority()
"realtime prioritization! Error: ");
throw std::runtime_error(errmsg + std::strerror(errno));
}
#endif
}

} // namespace nav2_util
Loading
Loading