Skip to content
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 3 additions & 16 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if (previous_publish_timestamp_ + publish_period_ <= time)
if (previous_publish_timestamp_ + publish_period_ > time)

I was misunderstanding the logic here. I think with this change and the earlier one everything should work. This should cause this if statement to pass as true the first time in simulation and from there on work correctly.

@christophfroehlich

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

still: This comparison will throw an exception if the timesource changes

{
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_;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
previous_publish_timestamp_ += publish_period_;
previous_publish_timestamp_ = time;

@christophfroehlich I think this should fix #585 and also be better overall.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

no because the comparison above fails if the time source changed.


if (should_publish)
{
if (realtime_odometry_publisher_)
{
odometry_message_.header.stamp = time;
Expand Down Expand Up @@ -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;
}
Expand Down