-
-
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 #102 from thinkabout4x/ros2_control_request
package request ros2_control
- Loading branch information
Showing
7 changed files
with
117 additions
and
18 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
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 | ||
{ |
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/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 |
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 |
---|---|---|
|
@@ -74,4 +74,7 @@ packages_select_by_deps: | |
|
||
- plotjuggler-ros | ||
- plotjuggler | ||
|
||
# package request | ||
- ros2_control | ||
patch_dir: patch |
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