Skip to content

Commit

Permalink
Merge pull request #102 from thinkabout4x/ros2_control_request
Browse files Browse the repository at this point in the history
package request ros2_control
  • Loading branch information
Tobias-Fischer authored Sep 14, 2023
2 parents 31598f5 + 54d0a3e commit 26c266b
Show file tree
Hide file tree
Showing 7 changed files with 117 additions and 18 deletions.
34 changes: 34 additions & 0 deletions patch/ros-humble-backward-ros.patch
Original file line number Diff line number Diff line change
@@ -1,3 +1,15 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 8927192..cb461f6 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -29,6 +29,7 @@ include(cmake/BackwardConfig.cmake)

set(CMAKE_CXX_STANDARD_REQUIRED True)
set(CMAKE_CXX_STANDARD 11)
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)

###############################################################################
# COMPILER FLAGS
diff --git a/cmake/BackwardConfigAment.cmake b/cmake/BackwardConfigAment.cmake
index 273a51a..d981cbb 100644
--- a/cmake/BackwardConfigAment.cmake
Expand All @@ -17,3 +29,25 @@ index 273a51a..d981cbb 100644
+
+SET(CMAKE_EXE_LINKER_FLAGS "${no_as_needed} ${backward_ros_full_path_LIBRARIES} ${as_needed} ${CMAKE_EXE_LINKER_FLAGS}")
+
diff --git a/cmake/BackwardConfig.cmake b/cmake/BackwardConfig.cmake
index 77d22d2..8e95287 100644
--- a/cmake/BackwardConfig.cmake
+++ b/cmake/BackwardConfig.cmake
@@ -125,11 +125,14 @@ endforeach()

set(BACKWARD_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}")

+set(FIND_PACKAGE_REQUIRED_VARS BACKWARD_INCLUDE_DIR)
+if(DEFINED BACKWARD_LIBRARIES)
+ list(APPEND FIND_PACKAGE_REQUIRED_VARS BACKWARD_LIBRARIES)
+endif()
+
include(FindPackageHandleStandardArgs)
find_package_handle_standard_args(Backward
- REQUIRED_VARS
- BACKWARD_INCLUDE_DIR
- BACKWARD_LIBRARIES
+ REQUIRED_VARS ${FIND_PACKAGE_REQUIRED_VARS}
)
list(APPEND _BACKWARD_INCLUDE_DIRS ${BACKWARD_INCLUDE_DIR})

13 changes: 13 additions & 0 deletions patch/ros-humble-controller-manager.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
diff --git a/controller_manager/include/controller_manager/controller_manager.hpp b/controller_manager/include/controller_manager/controller_manager.hpp
index 2850b2be8..5789f0d68 100644
--- a/controller_manager/include/controller_manager/controller_manager.hpp
+++ b/controller_manager/include/controller_manager/controller_manager.hpp
@@ -58,7 +58,7 @@ namespace controller_manager
{
using ControllersListIterator = std::vector<controller_manager::ControllerSpec>::const_iterator;

-rclcpp::NodeOptions get_cm_node_options();
+CONTROLLER_MANAGER_PUBLIC rclcpp::NodeOptions get_cm_node_options();

class ControllerManager : public rclcpp::Node
{
40 changes: 40 additions & 0 deletions patch/ros-humble-realtime-tools.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
diff --git a/src/thread_priority.cpp b/src/thread_priority.cpp
index 72749e3..778c06a 100644
--- a/src/thread_priority.cpp
+++ b/src/thread_priority.cpp
@@ -37,20 +37,12 @@ namespace realtime_tools
{
bool has_realtime_kernel()
{
- std::ifstream realtime_file("/sys/kernel/realtime", std::ios::in);
- bool has_realtime = false;
- if (realtime_file.is_open()) {
- realtime_file >> has_realtime;
- }
- return has_realtime;
+ return false;
}

bool configure_sched_fifo(int priority)
{
- struct sched_param schedp;
- memset(&schedp, 0, sizeof(schedp));
- schedp.sched_priority = priority;
- return !sched_setscheduler(0, SCHED_FIFO, &schedp);
+ return false;
}

} // namespace realtime_tools
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 4743d98..68fc981 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -5,6 +5,8 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra)
endif()

+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)
+
set(THIS_PACKAGE_INCLUDE_DEPENDS
rclcpp
rclcpp_action
3 changes: 3 additions & 0 deletions vinca_linux_aarch64.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,9 @@ packages_select_by_deps:
- vision-msgs
- slam-toolbox

# package request
- ros2_control

# - rviz2
# - behaviortree_cpp_v3
# - ros_workspace
Expand Down
4 changes: 4 additions & 0 deletions vinca_osx.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,10 @@ packages_select_by_deps:
- force_torque_sensor_broadcaster
- imu_sensor_broadcaster
- position_controllers

# package request
- ros2_control

# - joint-state-broadcaster
# - joint-state-publisher
# - joint-trajectory-controller
Expand Down
3 changes: 3 additions & 0 deletions vinca_osx_arm64.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -74,4 +74,7 @@ packages_select_by_deps:

- plotjuggler-ros
- plotjuggler

# package request
- ros2_control
patch_dir: patch
38 changes: 20 additions & 18 deletions vinca_win.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,15 +5,15 @@ conda_index:
- robostack.yaml
- packages-ignore.yaml

build_number: 3
build_number: 4

mutex_package: ros2-distro-mutex 0.3 humble

skip_all_deps: false

# If full rebuild, the build number of the existing package has
# to match the selected build number for skipping
full_rebuild: true
full_rebuild: false

packages_skip_by_deps:
- cartographer
Expand All @@ -39,27 +39,29 @@ skip_existing:

packages_select_by_deps:
# only subset of packages to reduce maintainer load
- vision_msgs

- ros2_control
- backward_ros
- ros_workspace
- ros_environment
- ros_base
# - vision_msgs
# - ros_environment
# - ros_base
# - navigation2
- moveit
- desktop_full
- desktop
- cv_bridge
- perception
# - moveit
# - desktop_full
# - desktop
# - cv_bridge
# - perception

- gazebo_msgs
- gazebo_dev
- gazebo_ros
- gazebo_plugins
- gazebo_ros_control
- gazebo_ros_pkgs
# - gazebo_msgs
# - gazebo_dev
# - gazebo_ros
# - gazebo_plugins
# - gazebo_ros_control
# - gazebo_ros_pkgs

- turtlebot3_simulations
# - turtlebot3_simulations

- rosbridge_suite
# - rosbridge_suite

patch_dir: patch

0 comments on commit 26c266b

Please sign in to comment.