diff --git a/diff_drive_controller/src/diff_drive_controller.cpp b/diff_drive_controller/src/diff_drive_controller.cpp index 92fa27a7be..fa56e31c31 100644 --- a/diff_drive_controller/src/diff_drive_controller.cpp +++ b/diff_drive_controller/src/diff_drive_controller.cpp @@ -219,24 +219,10 @@ controller_interface::return_type DiffDriveController::update_and_write_commands tf2::Quaternion orientation; orientation.setRPY(0.0, 0.0, odometry_.getHeading()); - bool should_publish = false; - try + if (previous_publish_timestamp_ + publish_period_ <= time) { - if (previous_publish_timestamp_ + publish_period_ <= time) - { - previous_publish_timestamp_ += publish_period_; - should_publish = true; - } - } - catch (const std::runtime_error &) - { - // Handle exceptions when the time source changes and initialize publish timestamp - previous_publish_timestamp_ = time; - should_publish = true; - } + previous_publish_timestamp_ += publish_period_; - if (should_publish) - { if (realtime_odometry_publisher_) { odometry_message_.header.stamp = time; @@ -492,6 +478,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure( odometry_transform_message_.transforms.front().header.frame_id = odom_frame_id; odometry_transform_message_.transforms.front().child_frame_id = base_frame_id; + previous_publish_timestamp_ = get_node()->get_clock()->now(); previous_update_timestamp_ = get_node()->get_clock()->now(); return controller_interface::CallbackReturn::SUCCESS; }