-
-
Notifications
You must be signed in to change notification settings - Fork 7
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 #19 from traversaro/addiitpkgs
Add various moveit, rviz, ur, twist_mux and zenoh packages required by IIT internal projects
- Loading branch information
Showing
28 changed files
with
2,092 additions
and
251 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
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
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/ackermann_steering_controller/CMakeLists.txt b/ackermann_steering_controller/CMakeLists.txt | ||
index 6ad0e9485f..874e9055b3 100644 | ||
--- a/ackermann_steering_controller/CMakeLists.txt | ||
+++ b/ackermann_steering_controller/CMakeLists.txt | ||
@@ -4,6 +4,7 @@ project(ackermann_steering_controller LANGUAGES CXX) | ||
if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") | ||
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion) | ||
endif() | ||
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) | ||
|
||
# find dependencies | ||
set(THIS_PACKAGE_INCLUDE_DEPENDS |
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,14 @@ | ||
|
||
diff --git a/admittance_controller/CMakeLists.txt b/admittance_controller/CMakeLists.txt | ||
index 884513deef..359e55b46d 100644 | ||
--- a/admittance_controller/CMakeLists.txt | ||
+++ b/admittance_controller/CMakeLists.txt | ||
@@ -7,6 +7,8 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") | ||
-Werror=missing-braces) | ||
endif() | ||
|
||
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) | ||
+ | ||
set(THIS_PACKAGE_INCLUDE_DEPENDS | ||
angles | ||
control_msgs |
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,17 @@ | ||
diff --git a/gz_ros2_control/CMakeLists.txt b/gz_ros2_control/CMakeLists.txt | ||
index 196f62d5..a7bdfd01 100644 | ||
--- a/gz_ros2_control/CMakeLists.txt | ||
+++ b/gz_ros2_control/CMakeLists.txt | ||
@@ -24,6 +24,12 @@ find_package(pluginlib REQUIRED) | ||
find_package(rclcpp REQUIRED) | ||
find_package(yaml_cpp_vendor REQUIRED) | ||
|
||
+# Compatibility with https://github.com/gazebosim/gz-cmake/blob/eb1c510e6278935eb742ed92c6a6d1388439f8bd/cmake/FindTINYXML2.cmake#L4 | ||
+if(NOT TARGET TINYXML2::TINYXML2) | ||
+ add_library(TINYXML2::TINYXML2 INTERFACE IMPORTED) | ||
+ set_property(TARGET tinyxml2::tinyxml2 PROPERTY INTERFACE_LINK_LIBRARIES tinyxml2::tinyxml2) | ||
+endif() | ||
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) | ||
find_package(gz_sim_vendor REQUIRED) | ||
find_package(gz-sim REQUIRED) | ||
|
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,40 @@ | ||
diff --git a/gz_ros2_control/CMakeLists.txt b/gz_ros2_control/CMakeLists.txt | ||
index 196f62d5..a7bdfd01 100644 | ||
--- a/gz_ros2_control/CMakeLists.txt | ||
+++ b/gz_ros2_control/CMakeLists.txt | ||
@@ -24,6 +24,12 @@ find_package(pluginlib REQUIRED) | ||
find_package(rclcpp REQUIRED) | ||
find_package(yaml_cpp_vendor REQUIRED) | ||
|
||
+# Compatibility with https://github.com/gazebosim/gz-cmake/blob/eb1c510e6278935eb742ed92c6a6d1388439f8bd/cmake/FindTINYXML2.cmake#L4 | ||
+if(NOT TARGET TINYXML2::TINYXML2) | ||
+ add_library(TINYXML2::TINYXML2 INTERFACE IMPORTED) | ||
+ set_property(TARGET tinyxml2::tinyxml2 PROPERTY INTERFACE_LINK_LIBRARIES tinyxml2::tinyxml2) | ||
+endif() | ||
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) | ||
find_package(gz_sim_vendor REQUIRED) | ||
find_package(gz-sim REQUIRED) | ||
|
||
diff --git a/gz_ros2_control/src/gz_ros2_control_plugin.cpp b/gz_ros2_control/src/gz_ros2_control_plugin.cpp | ||
index d38ce556..333d42a5 100644 | ||
--- a/gz_ros2_control/src/gz_ros2_control_plugin.cpp | ||
+++ b/gz_ros2_control/src/gz_ros2_control_plugin.cpp | ||
@@ -15,5 +15,3 @@ | ||
-#include <unistd.h> | ||
- | ||
#include <chrono> | ||
#include <map> | ||
#include <memory> | ||
|
||
diff --git a/gz_ros2_control/src/gz_system.cpp b/gz_ros2_control/src/gz_system.cpp | ||
index 5c9952b9..d5554d2c 100644 | ||
--- a/gz_ros2_control/src/gz_system.cpp | ||
+++ b/gz_ros2_control/src/gz_system.cpp | ||
@@ -51,3 +51,7 @@ | ||
+#ifdef ERROR | ||
+#undef ERROR | ||
+#endif | ||
+ | ||
struct jointData | ||
{ | ||
/// \brief Joint's names. |
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,15 @@ | ||
diff --git a/CMakeLists.txt b/CMakeLists.txt | ||
index afeadae..c1cc640 100644 | ||
--- a/CMakeLists.txt | ||
+++ b/CMakeLists.txt | ||
@@ -5,6 +5,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") | ||
add_compile_options(-Wall -Wextra -Wpedantic) | ||
endif() | ||
|
||
+# using this instead of visibility macros | ||
+# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053 | ||
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) | ||
+ | ||
set(THIS_PACKAGE_INCLUDE_DEPENDS | ||
kdl_parser | ||
kinematics_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,15 @@ | ||
diff --git a/CMakeLists.txt b/CMakeLists.txt | ||
index 88eaf9e..f0dbffd 100644 | ||
--- a/CMakeLists.txt | ||
+++ b/CMakeLists.txt | ||
@@ -5,6 +5,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") | ||
add_compile_options(-Wall -Wextra -Wpedantic) | ||
endif() | ||
|
||
+# using this instead of visibility macros | ||
+# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053 | ||
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) | ||
+ | ||
set(THIS_PACKAGE_INCLUDE_DEPENDS | ||
rclcpp | ||
rclcpp_lifecycle |
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,59 @@ | ||
|
||
diff --git a/moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp b/moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp | ||
index 8a6507c569..9c5d0805a6 100644 | ||
--- a/moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp | ||
+++ b/moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp | ||
@@ -45,8 +45,12 @@ | ||
#include <rclcpp/rclcpp.hpp> | ||
#include <signal.h> | ||
#include <stdio.h> | ||
+#ifndef WIN32 | ||
#include <termios.h> | ||
#include <unistd.h> | ||
+#else | ||
+#include <conio.h> | ||
+#endif | ||
|
||
// Define used keys | ||
namespace | ||
@@ -88,6 +92,7 @@ class KeyboardReader | ||
public: | ||
KeyboardReader() : file_descriptor_(0) | ||
{ | ||
+#ifndef WIN32 | ||
// get the console in raw mode | ||
tcgetattr(file_descriptor_, &cooked_); | ||
struct termios raw; | ||
@@ -97,23 +102,32 @@ class KeyboardReader | ||
raw.c_cc[VEOL] = 1; | ||
raw.c_cc[VEOF] = 2; | ||
tcsetattr(file_descriptor_, TCSANOW, &raw); | ||
+#endif | ||
} | ||
void readOne(char* c) | ||
{ | ||
+#ifndef WIN32 | ||
int rc = read(file_descriptor_, c, 1); | ||
if (rc < 0) | ||
{ | ||
throw std::runtime_error("read failed"); | ||
} | ||
+#else | ||
+ *c = static_cast<char>(_getch()); | ||
+#endif | ||
} | ||
void shutdown() | ||
{ | ||
+#ifndef WIN32 | ||
tcsetattr(file_descriptor_, TCSANOW, &cooked_); | ||
+#endif | ||
} | ||
|
||
private: | ||
int file_descriptor_; | ||
+#ifndef WIN32 | ||
struct termios cooked_; | ||
+#endif | ||
}; | ||
|
||
// Converts key-presses to Twist or Jog commands for Servo, in lieu of a 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,15 @@ | ||
diff --git a/steering_controllers_library/CMakeLists.txt b/steering_controllers_library/CMakeLists.txt | ||
index fc79d54b7c..2e80ed198f 100644 | ||
--- a/steering_controllers_library/CMakeLists.txt | ||
+++ b/steering_controllers_library/CMakeLists.txt | ||
@@ -7,6 +7,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") | ||
-Werror=missing-braces) | ||
endif() | ||
|
||
+# using this instead of visibility macros | ||
+# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053 | ||
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) | ||
+ | ||
# find dependencies | ||
set(THIS_PACKAGE_INCLUDE_DEPENDS | ||
control_msgs |
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,17 @@ | ||
diff --git a/cmake/Modules/FindTinyXML2.cmake b/cmake/Modules/FindTinyXML2.cmake | ||
index 87991be..5436d86 100644 | ||
--- a/cmake/Modules/FindTinyXML2.cmake | ||
+++ b/cmake/Modules/FindTinyXML2.cmake | ||
@@ -67,6 +67,12 @@ else() | ||
set_property(TARGET tinyxml2::tinyxml2 PROPERTY INTERFACE_INCLUDE_DIRECTORIES ${TINYXML2_INCLUDE_DIR}) | ||
list(APPEND TinyXML2_TARGETS tinyxml2::tinyxml2) | ||
endif() | ||
+ | ||
+ # Compatibility with https://github.com/gazebosim/gz-cmake/blob/eb1c510e6278935eb742ed92c6a6d1388439f8bd/cmake/FindTINYXML2.cmake#L4 | ||
+ if(NOT TARGET TINYXML2::TINYXML2) | ||
+ add_library(TINYXML2::TINYXML2 INTERFACE IMPORTED) | ||
+ set_property(TARGET TINYXML2::TINYXML2 PROPERTY INTERFACE_LINK_LIBRARIES tinyxml2::tinyxml2) | ||
+ endif() | ||
endif() | ||
|
||
# Set mixed case INCLUDE_DIRS and LIBRARY variables from upper case ones. |
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,31 @@ | ||
diff --git a/ur_calibration/CMakeLists.txt b/ur_calibration/CMakeLists.txt | ||
index 0b17e4d5f..31c63864f 100644 | ||
--- a/ur_calibration/CMakeLists.txt | ||
+++ b/ur_calibration/CMakeLists.txt | ||
@@ -2,10 +2,9 @@ cmake_minimum_required(VERSION 3.5) | ||
project(ur_calibration) | ||
|
||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") | ||
- add_compile_options(-Wall -Wextra -Wpedantic) | ||
+ add_compile_options(-Wall -Wextra -Wpedantic -Wno-unused-parameter) | ||
endif() | ||
- | ||
-add_compile_options(-Wno-unused-parameter) | ||
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) | ||
|
||
if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) | ||
message("${PROJECT_NAME}: You did not request a specific build type: selecting 'RelWithDebInfo'.") | ||
|
||
diff --git a/ur_calibration/CMakeLists.txt b/ur_calibration/CMakeLists.txt | ||
index 0b17e4d5f..8b8bbf871 100644 | ||
--- a/ur_calibration/CMakeLists.txt | ||
+++ b/ur_calibration/CMakeLists.txt | ||
@@ -37,7 +37,7 @@ target_include_directories(calibration | ||
${YAML_CPP_INCLUDE_DIRS} | ||
) | ||
target_link_libraries(calibration | ||
- ${YAML_CPP_LIBRARIES} | ||
+ yaml-cpp::yaml-cpp | ||
) | ||
ament_target_dependencies(calibration | ||
rclcpp |
Oops, something went wrong.