Compare commits
2 commits
Author | SHA1 | Date | |
---|---|---|---|
5f73198adb | |||
c44b7b8c3c |
5 changed files with 9 additions and 4 deletions
|
@ -13,6 +13,7 @@ endif()
|
||||||
|
|
||||||
# Find dependencies
|
# Find dependencies
|
||||||
find_package(ament_cmake REQUIRED)
|
find_package(ament_cmake REQUIRED)
|
||||||
|
find_package(tracetools REQUIRED)
|
||||||
find_package(rclcpp REQUIRED)
|
find_package(rclcpp REQUIRED)
|
||||||
find_package(rcl REQUIRED)
|
find_package(rcl REQUIRED)
|
||||||
find_package(rmw REQUIRED)
|
find_package(rmw REQUIRED)
|
||||||
|
@ -35,6 +36,7 @@ target_include_directories(priority_executor PUBLIC
|
||||||
$<INSTALL_INTERFACE:include>
|
$<INSTALL_INTERFACE:include>
|
||||||
)
|
)
|
||||||
ament_target_dependencies(priority_executor
|
ament_target_dependencies(priority_executor
|
||||||
|
tracetools
|
||||||
rmw
|
rmw
|
||||||
rclcpp
|
rclcpp
|
||||||
rcl
|
rcl
|
||||||
|
@ -54,6 +56,7 @@ target_link_libraries(usage_example
|
||||||
priority_executor
|
priority_executor
|
||||||
)
|
)
|
||||||
ament_target_dependencies(usage_example
|
ament_target_dependencies(usage_example
|
||||||
|
tracetools
|
||||||
rclcpp
|
rclcpp
|
||||||
std_msgs
|
std_msgs
|
||||||
std_srvs
|
std_srvs
|
||||||
|
|
|
@ -11,6 +11,7 @@
|
||||||
|
|
||||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||||
|
|
||||||
|
<depend>tracetools</depend>
|
||||||
<depend>rclcpp</depend>
|
<depend>rclcpp</depend>
|
||||||
<depend>rcl</depend>
|
<depend>rcl</depend>
|
||||||
<depend>rmw</depend>
|
<depend>rmw</depend>
|
||||||
|
|
|
@ -95,6 +95,7 @@ bool TimedExecutor::get_next_executable(
|
||||||
void
|
void
|
||||||
TimedExecutor::wait_for_work(std::chrono::nanoseconds timeout)
|
TimedExecutor::wait_for_work(std::chrono::nanoseconds timeout)
|
||||||
{
|
{
|
||||||
|
TRACEPOINT(rclcpp_executor_wait_for_work, timeout.count());
|
||||||
{
|
{
|
||||||
std::unique_lock<std::mutex> lock(memory_strategy_mutex_);
|
std::unique_lock<std::mutex> lock(memory_strategy_mutex_);
|
||||||
|
|
||||||
|
@ -166,6 +167,7 @@ TimedExecutor::wait_for_work(std::chrono::nanoseconds timeout)
|
||||||
bool
|
bool
|
||||||
TimedExecutor::get_next_ready_executable(rclcpp::AnyExecutable &any_executable)
|
TimedExecutor::get_next_ready_executable(rclcpp::AnyExecutable &any_executable)
|
||||||
{
|
{
|
||||||
|
TRACEPOINT(rclcpp_executor_get_next_ready);
|
||||||
bool success = false;
|
bool success = false;
|
||||||
if (use_priorities)
|
if (use_priorities)
|
||||||
{
|
{
|
||||||
|
|
|
@ -255,8 +255,8 @@ PriorityExecutable::PriorityExecutable(
|
||||||
ExecutableType t,
|
ExecutableType t,
|
||||||
ExecutableScheduleType sched_type) {
|
ExecutableScheduleType sched_type) {
|
||||||
handle = std::move(h);
|
handle = std::move(h);
|
||||||
std::cout << "priority_executable constructor called" << std::endl;
|
//std::cout << "priority_executable constructor called" << std::endl;
|
||||||
std::cout << "type: " << t << std::endl;
|
//std::cout << "type: " << t << std::endl;
|
||||||
type = t;
|
type = t;
|
||||||
|
|
||||||
if (sched_type == ExecutableScheduleType::CHAIN_INDEPENDENT_PRIORITY
|
if (sched_type == ExecutableScheduleType::CHAIN_INDEPENDENT_PRIORITY
|
||||||
|
|
|
@ -76,8 +76,7 @@ int main(int argc, char* argv[]) {
|
||||||
strategy->set_executable_deadline(talker->timer_->get_timer_handle(), 1000,
|
strategy->set_executable_deadline(talker->timer_->get_timer_handle(), 1000,
|
||||||
priority_executor::ExecutableType::TIMER, 0);
|
priority_executor::ExecutableType::TIMER, 0);
|
||||||
// you _must_ set the timer_handle for each chain
|
// you _must_ set the timer_handle for each chain
|
||||||
strategy->get_priority_settings(talker->timer_->get_timer_handle())
|
strategy->get_priority_settings(talker->timer_->get_timer_handle())->timer_handle = talker->timer_;
|
||||||
->timer_handle = talker->timer_;
|
|
||||||
// you _must_ mark the first executable in the chain
|
// you _must_ mark the first executable in the chain
|
||||||
strategy->set_first_in_chain(talker->timer_->get_timer_handle());
|
strategy->set_first_in_chain(talker->timer_->get_timer_handle());
|
||||||
// set the same period and chain_id for each callback in the chain
|
// set the same period and chain_id for each callback in the chain
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue