-
-
Notifications
You must be signed in to change notification settings - Fork 36
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #137 from traversaro/patch-3
Various Fixes for January Rebuild on Windows
- Loading branch information
Showing
19 changed files
with
610 additions
and
3 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,7 +1,5 @@ | ||
on: | ||
pull_request: | ||
paths: | ||
- '*.yaml' | ||
pull_request | ||
|
||
env: | ||
ROS_VERSION: 2 | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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<hardware_interface::CommandInterface> 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); | ||
}; | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 | ||
$<INSTALL_INTERFACE:include/control_toolbox> | ||
) | ||
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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,21 @@ | ||
From 4ebd2c68ab3eebb141c30a7ccf1dd6f9627328c1 Mon Sep 17 00:00:00 2001 | ||
From: Silvio Traversaro <silvio@traversaro.it> | ||
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. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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<hardware_interface::LoanedCommandInterface> velocity; | ||
}; | ||
|
||
+ DIFF_DRIVE_CONTROLLER_PUBLIC | ||
const char * feedback_type() const; | ||
controller_interface::CallbackReturn configure_side( | ||
const std::string & side, const std::vector<std::string> & 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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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<ParamListener> 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; |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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<const GripperCommandAction::Goal> goal); | ||
|
||
+ GRIPPER_ACTION_CONTROLLER_PUBLIC | ||
rclcpp_action::CancelResponse cancel_callback(const std::shared_ptr<GoalHandle> goal_handle); | ||
|
||
+ GRIPPER_ACTION_CONTROLLER_PUBLIC | ||
void accepted_callback(std::shared_ptr<GoalHandle> 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); |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 <stdexcept> | ||
#include <string> | ||
|
||
+#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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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: |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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<control_msgs::srv::QueryTrajectoryState::Request> request, | ||
std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response); |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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<ControllerStatePublisher> state_publisher_; | ||
|
||
// override methods from ChainableControllerInterface | ||
+ PID_CONTROLLER__VISIBILITY_PUBLIC | ||
std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override; | ||
|
||
+ PID_CONTROLLER__VISIBILITY_PUBLIC | ||
bool on_set_chained_mode(bool chained_mode) override; | ||
|
||
// internal methods |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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) |
Oops, something went wrong.