Skip to content

Commit 15c9be0

Browse files
Convert all wall timers and wall rates to ROS clock respecting rates and timers (#4000)
* Convert all wall timers and wall rates to ROS clock respecting rates and timers * linty mclint face * WPF wait plugin respect time * move duration metrics to use local clocks * bumping version for cache to break it * complete timing refactor * remove old variable
1 parent aa9396e commit 15c9be0

File tree

21 files changed

+44
-41
lines changed

21 files changed

+44
-41
lines changed

.circleci/config.yml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,12 +33,12 @@ _commands:
3333
- restore_cache:
3434
name: Restore Cache << parameters.key >>
3535
keys:
36-
- "<< parameters.key >>-v16\
36+
- "<< parameters.key >>-v17\
3737
-{{ arch }}\
3838
-{{ .Branch }}\
3939
-{{ .Environment.CIRCLE_PR_NUMBER }}\
4040
-{{ checksum \"<< parameters.workspace >>/lockfile.txt\" }}"
41-
- "<< parameters.key >>-v16\
41+
- "<< parameters.key >>-v17\
4242
-{{ arch }}\
4343
-main\
4444
-<no value>\
@@ -58,7 +58,7 @@ _commands:
5858
steps:
5959
- save_cache:
6060
name: Save Cache << parameters.key >>
61-
key: "<< parameters.key >>-v16\
61+
key: "<< parameters.key >>-v17\
6262
-{{ arch }}\
6363
-{{ .Branch }}\
6464
-{{ .Environment.CIRCLE_PR_NUMBER }}\

nav2_behavior_tree/include/nav2_behavior_tree/behavior_tree_engine.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include "behaviortree_cpp_v3/xml_parsing.h"
2626
#include "behaviortree_cpp_v3/loggers/bt_zmq_publisher.h"
2727

28+
#include "rclcpp/rclcpp.hpp"
2829

2930
namespace nav2_behavior_tree
3031
{
@@ -46,7 +47,8 @@ class BehaviorTreeEngine
4647
* @brief A constructor for nav2_behavior_tree::BehaviorTreeEngine
4748
* @param plugin_libraries vector of BT plugin library names to load
4849
*/
49-
explicit BehaviorTreeEngine(const std::vector<std::string> & plugin_libraries);
50+
explicit BehaviorTreeEngine(
51+
const std::vector<std::string> & plugin_libraries);
5052
virtual ~BehaviorTreeEngine() {}
5153

5254
/**

nav2_behavior_tree/src/behavior_tree_engine.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,8 @@
2525
namespace nav2_behavior_tree
2626
{
2727

28-
BehaviorTreeEngine::BehaviorTreeEngine(const std::vector<std::string> & plugin_libraries)
28+
BehaviorTreeEngine::BehaviorTreeEngine(
29+
const std::vector<std::string> & plugin_libraries)
2930
{
3031
BT::SharedLibrary loader;
3132
for (const auto & p : plugin_libraries) {

nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,7 @@ class DriveOnHeading : public TimedBehavior<ActionT>
7676
command_speed_ = command->speed;
7777
command_time_allowance_ = command->time_allowance;
7878

79-
end_time_ = this->steady_clock_.now() + command_time_allowance_;
79+
end_time_ = this->clock_->now() + command_time_allowance_;
8080

8181
if (!nav2_util::getCurrentPose(
8282
initial_pose_, *this->tf_, this->local_frame_, this->robot_base_frame_,
@@ -95,7 +95,7 @@ class DriveOnHeading : public TimedBehavior<ActionT>
9595
*/
9696
ResultStatus onCycleUpdate() override
9797
{
98-
rclcpp::Duration time_remaining = end_time_ - this->steady_clock_.now();
98+
rclcpp::Duration time_remaining = end_time_ - this->clock_->now();
9999
if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {
100100
this->stopRobot();
101101
RCLCPP_WARN(

nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -119,8 +119,8 @@ class TimedBehavior : public nav2_core::Behavior
119119
{
120120
node_ = parent;
121121
auto node = node_.lock();
122-
123122
logger_ = node->get_logger();
123+
clock_ = node->get_clock();
124124

125125
RCLCPP_INFO(logger_, "Configuring %s", name.c_str());
126126

@@ -200,7 +200,7 @@ class TimedBehavior : public nav2_core::Behavior
200200
rclcpp::Duration elasped_time_{0, 0};
201201

202202
// Clock
203-
rclcpp::Clock steady_clock_{RCL_STEADY_TIME};
203+
rclcpp::Clock::SharedPtr clock_;
204204

205205
// Logger
206206
rclcpp::Logger logger_{rclcpp::get_logger("nav2_behaviors")};
@@ -231,11 +231,11 @@ class TimedBehavior : public nav2_core::Behavior
231231
return;
232232
}
233233

234-
auto start_time = steady_clock_.now();
234+
auto start_time = clock_->now();
235235
rclcpp::WallRate loop_rate(cycle_frequency_);
236236

237237
while (rclcpp::ok()) {
238-
elasped_time_ = steady_clock_.now() - start_time;
238+
elasped_time_ = clock_->now() - start_time;
239239
if (action_server_->is_cancel_requested()) {
240240
RCLCPP_INFO(logger_, "Canceling %s", behavior_name_.c_str());
241241
stopRobot();
@@ -252,7 +252,7 @@ class TimedBehavior : public nav2_core::Behavior
252252
" however feature is currently not implemented. Aborting and stopping.",
253253
behavior_name_.c_str());
254254
stopRobot();
255-
result->total_elapsed_time = steady_clock_.now() - start_time;
255+
result->total_elapsed_time = clock_->now() - start_time;
256256
onActionCompletion(result);
257257
action_server_->terminate_current(result);
258258
return;
@@ -264,14 +264,14 @@ class TimedBehavior : public nav2_core::Behavior
264264
RCLCPP_INFO(
265265
logger_,
266266
"%s completed successfully", behavior_name_.c_str());
267-
result->total_elapsed_time = steady_clock_.now() - start_time;
267+
result->total_elapsed_time = clock_->now() - start_time;
268268
onActionCompletion(result);
269269
action_server_->succeeded_current(result);
270270
return;
271271

272272
case Status::FAILED:
273273
RCLCPP_WARN(logger_, "%s failed", behavior_name_.c_str());
274-
result->total_elapsed_time = steady_clock_.now() - start_time;
274+
result->total_elapsed_time = clock_->now() - start_time;
275275
result->error_code = on_cycle_update_result.error_code;
276276
onActionCompletion(result);
277277
action_server_->terminate_current(result);

nav2_behaviors/plugins/assisted_teleop.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ ResultStatus AssistedTeleop::onRun(const std::shared_ptr<const AssistedTeleopAct
6767
{
6868
preempt_teleop_ = false;
6969
command_time_allowance_ = command->time_allowance;
70-
end_time_ = steady_clock_.now() + command_time_allowance_;
70+
end_time_ = this->clock_->now() + command_time_allowance_;
7171
return ResultStatus{Status::SUCCEEDED, AssistedTeleopActionResult::NONE};
7272
}
7373

@@ -82,7 +82,7 @@ ResultStatus AssistedTeleop::onCycleUpdate()
8282
feedback_->current_teleop_duration = elasped_time_;
8383
action_server_->publish_feedback(feedback_);
8484

85-
rclcpp::Duration time_remaining = end_time_ - steady_clock_.now();
85+
rclcpp::Duration time_remaining = end_time_ - this->clock_->now();
8686
if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {
8787
stopRobot();
8888
RCLCPP_WARN_STREAM(
@@ -125,7 +125,7 @@ ResultStatus AssistedTeleop::onCycleUpdate()
125125
if (time == simulation_time_step_) {
126126
RCLCPP_DEBUG_STREAM_THROTTLE(
127127
logger_,
128-
steady_clock_,
128+
*clock_,
129129
1000,
130130
behavior_name_.c_str() << " collided on first time step, setting velocity to zero");
131131
scaled_twist.linear.x = 0.0f;
@@ -135,7 +135,7 @@ ResultStatus AssistedTeleop::onCycleUpdate()
135135
} else {
136136
RCLCPP_DEBUG_STREAM_THROTTLE(
137137
logger_,
138-
steady_clock_,
138+
*clock_,
139139
1000,
140140
behavior_name_.c_str() << " collision approaching in " << time << " seconds");
141141
double scale_factor = time / projection_time_;

nav2_behaviors/plugins/back_up.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ ResultStatus BackUp::onRun(const std::shared_ptr<const BackUpAction::Goal> comma
3131
command_speed_ = -std::fabs(command->speed);
3232
command_time_allowance_ = command->time_allowance;
3333

34-
end_time_ = steady_clock_.now() + command_time_allowance_;
34+
end_time_ = this->clock_->now() + command_time_allowance_;
3535

3636
if (!nav2_util::getCurrentPose(
3737
initial_pose_, *tf_, local_frame_, robot_base_frame_,

nav2_behaviors/plugins/spin.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -91,14 +91,14 @@ ResultStatus Spin::onRun(const std::shared_ptr<const SpinActionGoal> command)
9191
cmd_yaw_);
9292

9393
command_time_allowance_ = command->time_allowance;
94-
end_time_ = steady_clock_.now() + command_time_allowance_;
94+
end_time_ = this->clock_->now() + command_time_allowance_;
9595

9696
return ResultStatus{Status::SUCCEEDED, SpinActionResult::NONE};
9797
}
9898

9999
ResultStatus Spin::onCycleUpdate()
100100
{
101-
rclcpp::Duration time_remaining = end_time_ - steady_clock_.now();
101+
rclcpp::Duration time_remaining = end_time_ - this->clock_->now();
102102
if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {
103103
stopRobot();
104104
RCLCPP_WARN(

nav2_planner/include/nav2_planner/planner_server.hpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -241,9 +241,6 @@ class PlannerServer : public nav2_util::LifecycleNode
241241
double max_planner_duration_;
242242
std::string planner_ids_concat_;
243243

244-
// Clock
245-
rclcpp::Clock steady_clock_{RCL_STEADY_TIME};
246-
247244
// TF buffer
248245
std::shared_ptr<tf2_ros::Buffer> tf_;
249246

nav2_planner/src/planner_server.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -361,7 +361,7 @@ void PlannerServer::computePlanThroughPoses()
361361
{
362362
std::lock_guard<std::mutex> lock(dynamic_params_lock_);
363363

364-
auto start_time = steady_clock_.now();
364+
auto start_time = this->now();
365365

366366
// Initialize the ComputePathThroughPoses goal and result
367367
auto goal = action_server_poses_->get_current_goal();
@@ -421,7 +421,7 @@ void PlannerServer::computePlanThroughPoses()
421421
result->path = concat_path;
422422
publishPlan(result->path);
423423

424-
auto cycle_duration = steady_clock_.now() - start_time;
424+
auto cycle_duration = this->now() - start_time;
425425
result->planning_time = cycle_duration;
426426

427427
if (max_planner_duration_ && cycle_duration.seconds() > max_planner_duration_) {
@@ -480,7 +480,7 @@ PlannerServer::computePlan()
480480
{
481481
std::lock_guard<std::mutex> lock(dynamic_params_lock_);
482482

483-
auto start_time = steady_clock_.now();
483+
auto start_time = this->now();
484484

485485
// Initialize the ComputePathToPose goal and result
486486
auto goal = action_server_pose_->get_current_goal();
@@ -517,7 +517,7 @@ PlannerServer::computePlan()
517517
// Publish the plan for visualization purposes
518518
publishPlan(result->path);
519519

520-
auto cycle_duration = steady_clock_.now() - start_time;
520+
auto cycle_duration = this->now() - start_time;
521521
result->planning_time = cycle_duration;
522522

523523
if (max_planner_duration_ && cycle_duration.seconds() > max_planner_duration_) {

0 commit comments

Comments
 (0)