added tracepoints, removed cout
This commit is contained in:
parent
c44b7b8c3c
commit
5f73198adb
3 changed files with 5 additions and 4 deletions
|
@ -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