diff --git a/.github/workflows/testpr.yml b/.github/workflows/testpr.yml index b899e0ca..3b174d23 100644 --- a/.github/workflows/testpr.yml +++ b/.github/workflows/testpr.yml @@ -1,7 +1,5 @@ on: - pull_request: - paths: - - '*.yaml' + pull_request env: ROS_VERSION: 2 diff --git a/patch/ros-humble-ackermann-steering-controller.patch b/patch/ros-humble-ackermann-steering-controller.patch new file mode 100644 index 00000000..981b5bff --- /dev/null +++ b/patch/ros-humble-ackermann-steering-controller.patch @@ -0,0 +1,13 @@ +diff --git a/ackermann_steering_controller/CMakeLists.txt b/ackermann_steering_controller/CMakeLists.txt +index 66f09c5f09..71d0cf5f80 100644 +--- a/ackermann_steering_controller/CMakeLists.txt ++++ b/ackermann_steering_controller/CMakeLists.txt +@@ -44,7 +44,7 @@ ament_target_dependencies(ackermann_steering_controller PUBLIC ${THIS_PACKAGE_IN + + # Causes the visibility macros to use dllexport rather than dllimport, + # which is appropriate when building the dll but not consuming it. +-target_compile_definitions(ackermann_steering_controller PRIVATE "ACKERMANN_STEERING_CONTROLLER_BUILDING_DLL") ++target_compile_definitions(ackermann_steering_controller PRIVATE "ACKERMANN_STEERING_CONTROLLER__VISIBILITY_BUILDING_DLL") + + pluginlib_export_plugin_description_file( + controller_interface ackermann_steering_controller.xml) diff --git a/patch/ros-humble-admittance-controller.patch b/patch/ros-humble-admittance-controller.patch new file mode 100644 index 00000000..23bd8093 --- /dev/null +++ b/patch/ros-humble-admittance-controller.patch @@ -0,0 +1,37 @@ +diff --git a/include/admittance_controller/admittance_controller.hpp b/include/admittance_controller/admittance_controller.hpp +index b6473c6ff..3f1ccadbd 100644 +--- a/include/admittance_controller/admittance_controller.hpp ++++ b/include/admittance_controller/admittance_controller.hpp +@@ -95,8 +95,10 @@ public: + const rclcpp::Time & time, const rclcpp::Duration & period) override; + + protected: ++ ADMITTANCE_CONTROLLER_PUBLIC + std::vector on_export_reference_interfaces() override; + ++ ADMITTANCE_CONTROLLER_PUBLIC + controller_interface::return_type update_reference_from_subscribers() override; + + size_t num_joints_ = 0; +@@ -168,6 +170,7 @@ protected: + * @brief Read values from hardware interfaces and set corresponding fields of state_current and + * ft_values + */ ++ ADMITTANCE_CONTROLLER_PUBLIC + void read_state_from_hardware( + trajectory_msgs::msg::JointTrajectoryPoint & state_current, + geometry_msgs::msg::Wrench & ft_values); +@@ -176,11 +179,13 @@ protected: + * @brief Set fields of state_reference with values from controllers exported position and + * velocity references + */ ++ ADMITTANCE_CONTROLLER_PUBLIC + void read_state_reference_interfaces(trajectory_msgs::msg::JointTrajectoryPoint & state); + + /** + * @brief Write values from state_command to claimed hardware interfaces + */ ++ ADMITTANCE_CONTROLLER_PUBLIC + void write_state_to_hardware(const trajectory_msgs::msg::JointTrajectoryPoint & state_command); + }; + diff --git a/patch/ros-humble-bicycle-steering-controller.patch b/patch/ros-humble-bicycle-steering-controller.patch new file mode 100644 index 00000000..655272ed --- /dev/null +++ b/patch/ros-humble-bicycle-steering-controller.patch @@ -0,0 +1,13 @@ +diff --git a/bicycle_steering_controller/CMakeLists.txt b/bicycle_steering_controller/CMakeLists.txt +index 7118e9a44d..77d82ed874 100644 +--- a/bicycle_steering_controller/CMakeLists.txt ++++ b/bicycle_steering_controller/CMakeLists.txt +@@ -44,7 +44,7 @@ ament_target_dependencies(bicycle_steering_controller PUBLIC ${THIS_PACKAGE_INCL + + # Causes the visibility macros to use dllexport rather than dllimport, + # which is appropriate when building the dll but not consuming it. +-target_compile_definitions(bicycle_steering_controller PRIVATE "ACKERMANN_STEERING_CONTROLLER_BUILDING_DLL") ++target_compile_definitions(bicycle_steering_controller PRIVATE "BICYCLE_STEERING_CONTROLLER__VISIBILITY_BUILDING_DLL") + + pluginlib_export_plugin_description_file( + controller_interface bicycle_steering_controller.xml) diff --git a/patch/ros-humble-control-toolbox.patch b/patch/ros-humble-control-toolbox.patch new file mode 100644 index 00000000..d40c05da --- /dev/null +++ b/patch/ros-humble-control-toolbox.patch @@ -0,0 +1,12 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 7d3a2c7..4d5745c 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -73,6 +73,7 @@ target_include_directories(low_pass_filter PUBLIC + $ + ) + target_link_libraries(low_pass_filter PUBLIC low_pass_filter_parameters) ++set_target_properties(low_pass_filter PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + ament_target_dependencies(low_pass_filter PUBLIC ${CONTROL_FILTERS_INCLUDE_DEPENDS}) + + # Install pluginlib xml diff --git a/patch/ros-humble-controller-interface.patch b/patch/ros-humble-controller-interface.patch new file mode 100644 index 00000000..114d2f99 --- /dev/null +++ b/patch/ros-humble-controller-interface.patch @@ -0,0 +1,21 @@ +From 4ebd2c68ab3eebb141c30a7ccf1dd6f9627328c1 Mon Sep 17 00:00:00 2001 +From: Silvio Traversaro +Date: Mon, 12 Feb 2024 13:35:50 +0100 +Subject: [PATCH] Add missing export symbol in protected methods + +--- + .../controller_interface/chainable_controller_interface.hpp | 1 + + 1 file changed, 1 insertion(+) + +diff --git a/controller_interface/include/controller_interface/chainable_controller_interface.hpp b/controller_interface/include/controller_interface/chainable_controller_interface.hpp +index 2bdccefdc5..13c8b3f9b9 100644 +--- a/controller_interface/include/controller_interface/chainable_controller_interface.hpp ++++ b/controller_interface/include/controller_interface/chainable_controller_interface.hpp +@@ -88,6 +88,7 @@ class ChainableControllerInterface : public ControllerInterfaceBase + * \default returns true so the method don't have to be overridden if controller can always switch + * chained mode. + */ ++ CONTROLLER_INTERFACE_PUBLIC + virtual bool on_set_chained_mode(bool chained_mode); + + /// Update reference from input topics when not in chained mode. diff --git a/patch/ros-humble-diff-drive-controller.patch b/patch/ros-humble-diff-drive-controller.patch new file mode 100644 index 00000000..2e171b40 --- /dev/null +++ b/patch/ros-humble-diff-drive-controller.patch @@ -0,0 +1,22 @@ +diff --git a/include/diff_drive_controller/diff_drive_controller.hpp b/include/diff_drive_controller/diff_drive_controller.hpp +index 3584a1d1f..3c1336fb1 100644 +--- a/include/diff_drive_controller/diff_drive_controller.hpp ++++ b/include/diff_drive_controller/diff_drive_controller.hpp +@@ -98,6 +98,7 @@ protected: + std::reference_wrapper velocity; + }; + ++ DIFF_DRIVE_CONTROLLER_PUBLIC + const char * feedback_type() const; + controller_interface::CallbackReturn configure_side( + const std::string & side, const std::vector & wheel_names, +@@ -152,7 +153,9 @@ protected: + bool is_halted = false; + bool use_stamped_vel_ = true; + ++ DIFF_DRIVE_CONTROLLER_PUBLIC + bool reset(); ++ DIFF_DRIVE_CONTROLLER_PUBLIC + void halt(); + }; + } // namespace diff_drive_controller diff --git a/patch/ros-humble-forward-command-controller.patch b/patch/ros-humble-forward-command-controller.patch new file mode 100644 index 00000000..e7a62040 --- /dev/null +++ b/patch/ros-humble-forward-command-controller.patch @@ -0,0 +1,28 @@ +diff --git a/forward_command_controller/include/forward_command_controller/forward_command_controller.hpp b/forward_command_controller/include/forward_command_controller/forward_command_controller.hpp +index 91e3aae480..5c2de9131b 100644 +--- a/forward_command_controller/include/forward_command_controller/forward_command_controller.hpp ++++ b/forward_command_controller/include/forward_command_controller/forward_command_controller.hpp +@@ -44,7 +44,9 @@ class ForwardCommandController : public ForwardControllersBase + ForwardCommandController(); + + protected: ++ FORWARD_COMMAND_CONTROLLER_PUBLIC + void declare_parameters() override; ++ FORWARD_COMMAND_CONTROLLER_PUBLIC + controller_interface::CallbackReturn read_parameters() override; + + std::shared_ptr param_listener_; +diff --git a/forward_command_controller/include/forward_command_controller/multi_interface_forward_command_controller.hpp b/forward_command_controller/include/forward_command_controller/multi_interface_forward_command_controller.hpp +index fd7c0d480e..3881c1c9d4 100644 +--- a/forward_command_controller/include/forward_command_controller/multi_interface_forward_command_controller.hpp ++++ b/forward_command_controller/include/forward_command_controller/multi_interface_forward_command_controller.hpp +@@ -44,7 +44,9 @@ class MultiInterfaceForwardCommandController + MultiInterfaceForwardCommandController(); + + protected: ++ FORWARD_COMMAND_CONTROLLER_PUBLIC + void declare_parameters() override; ++ FORWARD_COMMAND_CONTROLLER_PUBLIC + controller_interface::CallbackReturn read_parameters() override; + + using Params = multi_interface_forward_command_controller::Params; diff --git a/patch/ros-humble-gripper-controllers.patch b/patch/ros-humble-gripper-controllers.patch new file mode 100644 index 00000000..ab9581e1 --- /dev/null +++ b/patch/ros-humble-gripper-controllers.patch @@ -0,0 +1,48 @@ +diff --git a/gripper_controllers/CMakeLists.txt b/gripper_controllers/CMakeLists.txt +index 676062f7a3..c4a85dd453 100644 +--- a/gripper_controllers/CMakeLists.txt ++++ b/gripper_controllers/CMakeLists.txt +@@ -45,6 +45,10 @@ target_link_libraries(gripper_action_controller PUBLIC + ) + ament_target_dependencies(gripper_action_controller PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) + ++# Causes the visibility macros to use dllexport rather than dllimport, ++# which is appropriate when building the dll but not consuming it. ++target_compile_definitions(gripper_action_controller PRIVATE "GRIPPER_ACTION_CONTROLLER_BUILDING_DLL") ++ + pluginlib_export_plugin_description_file(controller_interface ros_control_plugins.xml) + + if(BUILD_TESTING) +diff --git a/gripper_controllers/include/gripper_controllers/gripper_action_controller.hpp b/gripper_controllers/include/gripper_controllers/gripper_action_controller.hpp +index 38e0bd8191..2762cbf611 100644 +--- a/gripper_controllers/include/gripper_controllers/gripper_action_controller.hpp ++++ b/gripper_controllers/include/gripper_controllers/gripper_action_controller.hpp +@@ -148,15 +148,20 @@ class GripperActionController : public controller_interface::ControllerInterface + + rclcpp::TimerBase::SharedPtr goal_handle_timer_; + ++ GRIPPER_ACTION_CONTROLLER_PUBLIC + rclcpp_action::GoalResponse goal_callback( + const rclcpp_action::GoalUUID & uuid, std::shared_ptr goal); + ++ GRIPPER_ACTION_CONTROLLER_PUBLIC + rclcpp_action::CancelResponse cancel_callback(const std::shared_ptr goal_handle); + ++ GRIPPER_ACTION_CONTROLLER_PUBLIC + void accepted_callback(std::shared_ptr goal_handle); + ++ GRIPPER_ACTION_CONTROLLER_PUBLIC + void preempt_active_goal(); + ++ GRIPPER_ACTION_CONTROLLER_PUBLIC + void set_hold_position(); + + rclcpp::Time last_movement_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME); ///< Store stall time +@@ -165,6 +170,7 @@ class GripperActionController : public controller_interface::ControllerInterface + /** + * \brief Check for success and publish appropriate result and feedback. + **/ ++ GRIPPER_ACTION_CONTROLLER_PUBLIC + void check_for_success( + const rclcpp::Time & time, double error_position, double current_position, + double current_velocity); diff --git a/patch/ros-humble-hardware-interface.patch b/patch/ros-humble-hardware-interface.patch new file mode 100644 index 00000000..e60ae176 --- /dev/null +++ b/patch/ros-humble-hardware-interface.patch @@ -0,0 +1,24 @@ +diff --git a/hardware_interface/include/hardware_interface/lexical_casts.hpp b/hardware_interface/include/hardware_interface/lexical_casts.hpp +index 846d9f757c..042361e392 100644 +--- a/hardware_interface/include/hardware_interface/lexical_casts.hpp ++++ b/hardware_interface/include/hardware_interface/lexical_casts.hpp +@@ -21,6 +21,8 @@ + #include + #include + ++#include "hardware_interface/visibility_control.h" ++ + namespace hardware_interface + { + +@@ -29,8 +31,10 @@ namespace hardware_interface + * from + https://github.com/ros-planning/srdfdom/blob/ad17b8d25812f752c397a6011cec64aeff090c46/src/model.cpp#L53 + */ ++HARDWARE_INTERFACE_PUBLIC + double stod(const std::string & s); + ++HARDWARE_INTERFACE_PUBLIC + bool parse_bool(const std::string & bool_string); + + } // namespace hardware_interface diff --git a/patch/ros-humble-joint-state-broadcaster.patch b/patch/ros-humble-joint-state-broadcaster.patch new file mode 100644 index 00000000..3228b461 --- /dev/null +++ b/patch/ros-humble-joint-state-broadcaster.patch @@ -0,0 +1,18 @@ +diff --git a/joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp b/joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp +index f1c532dce9..9eb7ab8a13 100644 +--- a/joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp ++++ b/joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp +@@ -88,9 +88,13 @@ class JointStateBroadcaster : public controller_interface::ControllerInterface + const rclcpp_lifecycle::State & previous_state) override; + + protected: ++ JOINT_STATE_BROADCASTER_PUBLIC + bool init_joint_data(); ++ JOINT_STATE_BROADCASTER_PUBLIC + void init_joint_state_msg(); ++ JOINT_STATE_BROADCASTER_PUBLIC + void init_dynamic_joint_state_msg(); ++ JOINT_STATE_BROADCASTER_PUBLIC + bool use_all_available_interfaces() const; + + protected: diff --git a/patch/ros-humble-joint-trajectory-controller.patch b/patch/ros-humble-joint-trajectory-controller.patch new file mode 100644 index 00000000..cb3354c4 --- /dev/null +++ b/patch/ros-humble-joint-trajectory-controller.patch @@ -0,0 +1,25 @@ +diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +index 111837cc17..df3b192c6d 100644 +--- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp ++++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +@@ -271,6 +271,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa + const rclcpp::Time & time, const JointTrajectoryPoint & desired_state, + const JointTrajectoryPoint & current_state, const JointTrajectoryPoint & state_error); + ++ JOINT_TRAJECTORY_CONTROLLER_PUBLIC + void read_state_from_state_interfaces(JointTrajectoryPoint & state); + + /** Assign values from the command interfaces as state. +@@ -279,9 +280,12 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa + * @param[out] state to be filled with values from command interfaces. + * @return true if all interfaces exists and contain non-NaN values, false otherwise. + */ ++ JOINT_TRAJECTORY_CONTROLLER_PUBLIC + bool read_state_from_command_interfaces(JointTrajectoryPoint & state); ++ JOINT_TRAJECTORY_CONTROLLER_PUBLIC + bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands); + ++ JOINT_TRAJECTORY_CONTROLLER_PUBLIC + void query_state_service( + const std::shared_ptr request, + std::shared_ptr response); diff --git a/patch/ros-humble-pid-controller.patch b/patch/ros-humble-pid-controller.patch new file mode 100644 index 00000000..3fc24fef --- /dev/null +++ b/patch/ros-humble-pid-controller.patch @@ -0,0 +1,28 @@ +diff --git a/pid_controller/CMakeLists.txt b/pid_controller/CMakeLists.txt +index 15e903222a..6c9e00ef8b 100644 +--- a/pid_controller/CMakeLists.txt ++++ b/pid_controller/CMakeLists.txt +@@ -45,7 +45,7 @@ ament_target_dependencies(pid_controller PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) + + # Causes the visibility macros to use dllexport rather than dllimport, + # which is appropriate when building the dll but not consuming it. +-target_compile_definitions(pid_controller PRIVATE "PID_CONTROLLER_BUILDING_DLL") ++target_compile_definitions(pid_controller PRIVATE "PID_CONTROLLER__VISIBILITY_BUILDING_DLL") + + pluginlib_export_plugin_description_file(controller_interface pid_controller.xml) + +diff --git a/pid_controller/include/pid_controller/pid_controller.hpp b/pid_controller/include/pid_controller/pid_controller.hpp +index f7b8cc4491..788f39f1ed 100644 +--- a/pid_controller/include/pid_controller/pid_controller.hpp ++++ b/pid_controller/include/pid_controller/pid_controller.hpp +@@ -121,8 +121,10 @@ class PidController : public controller_interface::ChainableControllerInterface + std::unique_ptr state_publisher_; + + // override methods from ChainableControllerInterface ++ PID_CONTROLLER__VISIBILITY_PUBLIC + std::vector on_export_reference_interfaces() override; + ++ PID_CONTROLLER__VISIBILITY_PUBLIC + bool on_set_chained_mode(bool chained_mode) override; + + // internal methods diff --git a/patch/ros-humble-rsl.win.patch b/patch/ros-humble-rsl.win.patch new file mode 100644 index 00000000..80c72407 --- /dev/null +++ b/patch/ros-humble-rsl.win.patch @@ -0,0 +1,26 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 6d47b08..1b0c4f0 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -30,6 +37,21 @@ target_link_libraries(rsl PUBLIC + tl_expected::tl_expected + ) + ++# There is no explicit export of symbols in the library either via ++# hand-written ***_export.h headers or generate_export_header CMake macro, ++# as the header-only functions in this library are quite limited in number, ++# it is perfectly ok to export all of them (as done in *nix) with the ++# WINDOWS_EXPORT_ALL_SYMBOLS property ++if(MSVC) ++ set_target_properties(rsl PROPERTIES ++ WINDOWS_EXPORT_ALL_SYMBOLS TRUE ++ ) ++ # On Windows, also ensure that all .dll libraries are placed in the ++ # same build directory so they can be found by the loader (there is ++ # no rpath on Windows) ++ set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_BINDIR}") ++endif() ++ + add_subdirectory(docs) + + option(RSL_BUILD_TESTING "Build tests" OFF) diff --git a/patch/ros-humble-steering-controllers-library.patch b/patch/ros-humble-steering-controllers-library.patch new file mode 100644 index 00000000..3bc76571 --- /dev/null +++ b/patch/ros-humble-steering-controllers-library.patch @@ -0,0 +1,192 @@ +diff --git a/steering_controllers_library/CMakeLists.txt b/steering_controllers_library/CMakeLists.txt +index 88f24d304c..106fdcc464 100644 +--- a/steering_controllers_library/CMakeLists.txt ++++ b/steering_controllers_library/CMakeLists.txt +@@ -51,7 +51,7 @@ ament_target_dependencies(steering_controllers_library PUBLIC ${THIS_PACKAGE_INC + + # Causes the visibility macros to use dllexport rather than dllimport, + # which is appropriate when building the dll but not consuming it. +-target_compile_definitions(steering_controllers_library PRIVATE "STEERING_CONTROLLERS_BUILDING_DLL") ++target_compile_definitions(steering_controllers_library PRIVATE "STEERING_CONTROLLERS__VISIBILITY_BUILDING_DLL" "_USE_MATH_DEFINES") + + if(BUILD_TESTING) + find_package(ament_cmake_gmock REQUIRED) +diff --git a/steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp b/steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp +index b560e2a782..5e3264fd67 100644 +--- a/steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp ++++ b/steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp +@@ -89,7 +89,7 @@ class SteeringControllersLibrary : public controller_interface::ChainableControl + using AckermanControllerState = control_msgs::msg::SteeringControllerStatus; + + protected: +- controller_interface::CallbackReturn set_interface_numbers( ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn set_interface_numbers( + size_t nr_state_itfs, size_t nr_cmd_itfs, size_t nr_ref_itfs); + + std::shared_ptr param_listener_; +@@ -112,9 +112,9 @@ class SteeringControllersLibrary : public controller_interface::ChainableControl + std::unique_ptr rt_tf_odom_state_publisher_; + + // override methods from ChainableControllerInterface +- std::vector on_export_reference_interfaces() override; ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC std::vector on_export_reference_interfaces() override; + +- bool on_set_chained_mode(bool chained_mode) override; ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC bool on_set_chained_mode(bool chained_mode) override; + + /// Odometry: + steering_odometry::SteeringOdometry odometry_; +diff --git a/steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp b/steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp +index 95bcef7e63..f1d63287cd 100644 +--- a/steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp ++++ b/steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp +@@ -26,6 +26,8 @@ + + #include "rcpputils/rolling_mean_accumulator.hpp" + ++#include "steering_controllers_library/visibility_control.h" ++ + namespace steering_odometry + { + const unsigned int BICYCLE_CONFIG = 0; +@@ -45,12 +47,14 @@ class SteeringOdometry + * \param velocity_rolling_window_size Rolling window size used to compute the velocity mean + * + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + explicit SteeringOdometry(size_t velocity_rolling_window_size = 10); + + /** + * \brief Initialize the odometry + * \param time Current time + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + void init(const rclcpp::Time & time); + + /** +@@ -60,6 +64,7 @@ class SteeringOdometry + * \param dt time difference to last call + * \return true if the odometry is actually updated + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + bool update_from_position( + const double traction_wheel_pos, const double steer_pos, const double dt); + +@@ -71,6 +76,7 @@ class SteeringOdometry + * \param dt time difference to last call + * \return true if the odometry is actually updated + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + bool update_from_position( + const double right_traction_wheel_pos, const double left_traction_wheel_pos, + const double steer_pos, const double dt); +@@ -84,6 +90,7 @@ class SteeringOdometry + * \param dt time difference to last call + * \return true if the odometry is actually updated + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + bool update_from_position( + const double right_traction_wheel_pos, const double left_traction_wheel_pos, + const double right_steer_pos, const double left_steer_pos, const double dt); +@@ -95,6 +102,7 @@ class SteeringOdometry + * \param dt time difference to last call + * \return true if the odometry is actually updated + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + bool update_from_velocity( + const double traction_wheel_vel, const double steer_pos, const double dt); + +@@ -106,6 +114,7 @@ class SteeringOdometry + * \param dt time difference to last call + * \return true if the odometry is actually updated + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + bool update_from_velocity( + const double right_traction_wheel_vel, const double left_traction_wheel_vel, + const double steer_pos, const double dt); +@@ -119,6 +128,7 @@ class SteeringOdometry + * \param dt time difference to last call + * \return true if the odometry is actually updated + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + bool update_from_velocity( + const double right_traction_wheel_vel, const double left_traction_wheel_vel, + const double right_steer_pos, const double left_steer_pos, const double dt); +@@ -129,53 +139,62 @@ class SteeringOdometry + * \param angular Angular velocity [rad/s] + * \param time Current time + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + void update_open_loop(const double linear, const double angular, const double dt); + + /** + * \brief Set odometry type + * \param type odometry type + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + void set_odometry_type(const unsigned int type); + + /** + * \brief heading getter + * \return heading [rad] + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + double get_heading() const { return heading_; } + + /** + * \brief x position getter + * \return x position [m] + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + double get_x() const { return x_; } + + /** + * \brief y position getter + * \return y position [m] + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + double get_y() const { return y_; } + + /** + * \brief linear velocity getter + * \return linear velocity [m/s] + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + double get_linear() const { return linear_; } + + /** + * \brief angular velocity getter + * \return angular velocity [rad/s] + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + double get_angular() const { return angular_; } + + /** + * \brief Sets the wheel parameters: radius, separation and wheelbase + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + void set_wheel_params(double wheel_radius, double wheelbase = 0.0, double wheel_track = 0.0); + + /** + * \brief Velocity rolling window size setter + * \param velocity_rolling_window_size Velocity rolling window size + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + void set_velocity_rolling_window_size(size_t velocity_rolling_window_size); + + /** +@@ -184,12 +203,14 @@ class SteeringOdometry + * \param theta_dot Desired angular velocity [rad/s] + * \return Tuple of velocity commands and steering commands + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + std::tuple, std::vector> get_commands( + const double Vx, const double theta_dot); + + /** + * \brief Reset poses, heading, and accumulators + */ ++ STEERING_CONTROLLERS__VISIBILITY_PUBLIC + void reset_odometry(); + + private: diff --git a/patch/ros-humble-tricycle-controller.patch b/patch/ros-humble-tricycle-controller.patch new file mode 100644 index 00000000..954f61e6 --- /dev/null +++ b/patch/ros-humble-tricycle-controller.patch @@ -0,0 +1,47 @@ +diff --git a/tricycle_controller/CMakeLists.txt b/tricycle_controller/CMakeLists.txt +index cdc69f182a..94fba916b1 100644 +--- a/tricycle_controller/CMakeLists.txt ++++ b/tricycle_controller/CMakeLists.txt +@@ -47,6 +47,7 @@ target_include_directories(tricycle_controller PUBLIC + ) + target_link_libraries(tricycle_controller PUBLIC tricycle_controller_parameters) + ament_target_dependencies(tricycle_controller PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) ++target_compile_definitions(tricycle_controller PRIVATE "TRICYCLE_CONTROLLER_BUILDING_DLL" _USE_MATH_DEFINES) + + pluginlib_export_plugin_description_file(controller_interface tricycle_controller.xml) + +diff --git a/tricycle_controller/include/tricycle_controller/tricycle_controller.hpp b/tricycle_controller/include/tricycle_controller/tricycle_controller.hpp +index 24aaf89de9..f76451d607 100644 +--- a/tricycle_controller/include/tricycle_controller/tricycle_controller.hpp ++++ b/tricycle_controller/include/tricycle_controller/tricycle_controller.hpp +@@ -105,11 +105,15 @@ class TricycleController : public controller_interface::ControllerInterface + std::reference_wrapper position_command; + }; + ++ TRICYCLE_CONTROLLER_PUBLIC + CallbackReturn get_traction( + const std::string & traction_joint_name, std::vector & joint); ++ TRICYCLE_CONTROLLER_PUBLIC + CallbackReturn get_steering( + const std::string & steering_joint_name, std::vector & joint); ++ TRICYCLE_CONTROLLER_PUBLIC + double convert_trans_rot_vel_to_steering_angle(double v, double omega, double wheelbase); ++ TRICYCLE_CONTROLLER_PUBLIC + std::tuple twist_to_ackermann(double linear_command, double angular_command); + + // Parameters from ROS for tricycle_controller +@@ -155,11 +159,14 @@ class TricycleController : public controller_interface::ControllerInterface + + bool is_halted = false; + ++ TRICYCLE_CONTROLLER_PUBLIC + void reset_odometry( + const std::shared_ptr request_header, + const std::shared_ptr req, + std::shared_ptr res); ++ TRICYCLE_CONTROLLER_PUBLIC + bool reset(); ++ TRICYCLE_CONTROLLER_PUBLIC + void halt(); + }; + } // namespace tricycle_controller \ No newline at end of file diff --git a/patch/ros-humble-tricycle-steering-controller.patch b/patch/ros-humble-tricycle-steering-controller.patch new file mode 100644 index 00000000..7145d810 --- /dev/null +++ b/patch/ros-humble-tricycle-steering-controller.patch @@ -0,0 +1,34 @@ +diff --git a/tricycle_steering_controller/CMakeLists.txt b/tricycle_steering_controller/CMakeLists.txt +index 02c9453ace..21604df0c4 100644 +--- a/tricycle_steering_controller/CMakeLists.txt ++++ b/tricycle_steering_controller/CMakeLists.txt +@@ -44,7 +44,7 @@ ament_target_dependencies(tricycle_steering_controller PUBLIC ${THIS_PACKAGE_INC + + # Causes the visibility macros to use dllexport rather than dllimport, + # which is appropriate when building the dll but not consuming it. +-target_compile_definitions(tricycle_steering_controller PRIVATE "ACKERMANN_STEERING_CONTROLLER_BUILDING_DLL") ++target_compile_definitions(tricycle_steering_controller PRIVATE "TRICYCLE_STEERING_CONTROLLER__VISIBILITY_BUILDING_DLL") + + pluginlib_export_plugin_description_file( + controller_interface tricycle_steering_controller.xml) +diff --git a/tricycle_steering_controller/include/tricycle_steering_controller/tricycle_steering_controller.hpp b/tricycle_steering_controller/include/tricycle_steering_controller/tricycle_steering_controller.hpp +index 607a684df5..0ae5db0a26 100644 +--- a/tricycle_steering_controller/include/tricycle_steering_controller/tricycle_steering_controller.hpp ++++ b/tricycle_steering_controller/include/tricycle_steering_controller/tricycle_steering_controller.hpp +@@ -45,13 +45,13 @@ class TricycleSteeringController : public steering_controllers_library::Steering + public: + TricycleSteeringController(); + +- STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn configure_odometry() ++ TRICYCLE_STEERING_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn configure_odometry() + override; + +- STEERING_CONTROLLERS__VISIBILITY_PUBLIC bool update_odometry( ++ TRICYCLE_STEERING_CONTROLLER__VISIBILITY_PUBLIC bool update_odometry( + const rclcpp::Duration & period) override; + +- STEERING_CONTROLLERS__VISIBILITY_PUBLIC void initialize_implementation_parameter_listener() ++ TRICYCLE_STEERING_CONTROLLER__VISIBILITY_PUBLIC void initialize_implementation_parameter_listener() + override; + + protected: diff --git a/patch/ros-humble-yaml-cpp-vendor.patch b/patch/ros-humble-yaml-cpp-vendor.patch new file mode 100644 index 00000000..d2f19b0c --- /dev/null +++ b/patch/ros-humble-yaml-cpp-vendor.patch @@ -0,0 +1,20 @@ +From 25757ddc5272ea80a099c4b8fb7c4c90708416e4 Mon Sep 17 00:00:00 2001 +From: Silvio Traversaro +Date: Sat, 10 Feb 2024 16:14:21 +0100 +Subject: [PATCH] Support yaml-cpp >= 0.8.0 + +Signed-off-by: Silvio Traversaro +--- + yaml_cpp_vendor-extras.cmake.in | 17 +++++++++++------ + 1 file changed, 11 insertions(+), 6 deletions(-) + +diff --git a/yaml_cpp_vendor-extras.cmake.in b/yaml_cpp_vendor-extras.cmake.in +index deac98c..48eb4a9 100644 +--- a/yaml_cpp_vendor-extras.cmake.in ++++ b/yaml_cpp_vendor-extras.cmake.in +@@ -15,4 +15,4 @@ endif() + set(yaml_cpp_vendor_LIBRARIES ${YAML_CPP_LIBRARIES}) + set(yaml_cpp_vendor_INCLUDE_DIRS ${YAML_CPP_INCLUDE_DIR}) + +-list(APPEND yaml_cpp_vendor_TARGETS yaml-cpp) ++list(APPEND yaml_cpp_vendor_TARGETS yaml-cpp::yaml-cpp) diff --git a/vinca_win.yaml b/vinca_win.yaml index 4f5d9d39..96cbad70 100644 --- a/vinca_win.yaml +++ b/vinca_win.yaml @@ -63,3 +63,4 @@ packages_select_by_deps: # - moveit patch_dir: patch +