Skip to content

Commit 68c62fd

Browse files
committed
Parse thread scheduler priority parsing to the async handlers
1 parent 99ce092 commit 68c62fd

File tree

3 files changed

+12
-3
lines changed

3 files changed

+12
-3
lines changed

hardware_interface/include/hardware_interface/actuator_interface.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -114,6 +114,8 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
114114
info_ = hardware_info;
115115
if (info_.is_async)
116116
{
117+
RCLCPP_INFO_STREAM(
118+
get_logger(), "Starting async handler with scheduler priority: " << info_.thread_priority);
117119
async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
118120
async_handler_->init(
119121
[this](const rclcpp::Time & time, const rclcpp::Duration & period)
@@ -130,7 +132,8 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
130132
next_trigger_ = TriggerType::READ;
131133
return ret;
132134
}
133-
});
135+
},
136+
info_.thread_priority);
134137
async_handler_->start_thread();
135138
}
136139
return on_init(hardware_info);

hardware_interface/include/hardware_interface/sensor_interface.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -114,9 +114,12 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
114114
info_ = hardware_info;
115115
if (info_.is_async)
116116
{
117+
RCLCPP_INFO_STREAM(
118+
get_logger(), "Starting async handler with scheduler priority: " << info_.thread_priority);
117119
read_async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
118120
read_async_handler_->init(
119-
std::bind(&SensorInterface::read, this, std::placeholders::_1, std::placeholders::_2));
121+
std::bind(&SensorInterface::read, this, std::placeholders::_1, std::placeholders::_2),
122+
info_.thread_priority);
120123
read_async_handler_->start_thread();
121124
}
122125
return on_init(hardware_info);

hardware_interface/include/hardware_interface/system_interface.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -117,6 +117,8 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
117117
info_ = hardware_info;
118118
if (info_.is_async)
119119
{
120+
RCLCPP_INFO_STREAM(
121+
get_logger(), "Starting async handler with scheduler priority: " << info_.thread_priority);
120122
async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
121123
async_handler_->init(
122124
[this](const rclcpp::Time & time, const rclcpp::Duration & period)
@@ -133,7 +135,8 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
133135
next_trigger_ = TriggerType::READ;
134136
return ret;
135137
}
136-
});
138+
},
139+
info_.thread_priority);
137140
async_handler_->start_thread();
138141
}
139142
return on_init(hardware_info);

0 commit comments

Comments
 (0)