Skip to content

add read_only parameters to diff_drive_controller #1781

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Draft
wants to merge 7 commits into
base: master
Choose a base branch
from

Conversation

adhithiyan110
Copy link

This PR adds the read_only attribute to key parameters of diff_drive_controller.Related to #1696

@adhithiyan110 adhithiyan110 requested a review from saikishor July 6, 2025 05:11
Copy link
Contributor

@christophfroehlich christophfroehlich left a comment

Choose a reason for hiding this comment

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

The parameters itself look good. But we don't update the parameters post on_configure. I propose changing this to a simple get_params() as on_configure is not in the RT thread

// update parameters if they have changed
if (param_listener_->try_update_params(params_))
{
RCLCPP_INFO(logger, "Parameters were updated");
}

but add this try_update_params to the update_reference_from_subscribers or update_and_write_commands method.

Please review then also if we need local copies of the params_-struct members and either remove it or update them after try_update_params. (cmd_vel_timeout_, publish_limited_velocity_,..)

@christophfroehlich
Copy link
Contributor

@adhithiyan110 do you need any input for going on with this PR?

@christophfroehlich christophfroehlich marked this pull request as draft July 26, 2025 11:12
@adhithiyan110
Copy link
Author

@christophfroehlich can you please review changes

Comment on lines +118 to +126
// limit the publication on the topics /odom and /tf
publish_rate_ = params_.publish_rate;
publish_period_ = rclcpp::Duration::from_seconds(1.0 / publish_rate_);
const double wheel_separation = params_.wheel_separation_multiplier * params_.wheel_separation;
const double left_wheel_radius = params_.left_wheel_radius_multiplier * params_.wheel_radius;
const double right_wheel_radius = params_.right_wheel_radius_multiplier * params_.wheel_radius;

odometry_.setWheelParams(wheel_separation, left_wheel_radius, right_wheel_radius);
odometry_.setVelocityRollingWindowSize(static_cast<size_t>(params_.velocity_rolling_window_size));
Copy link
Contributor

Choose a reason for hiding this comment

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

these parameters are read-only, better leave them in on_configure

Comment on lines +128 to +138
limiter_linear_ = std::make_unique<SpeedLimiter>(
params_.linear.x.min_velocity, params_.linear.x.max_velocity,
params_.linear.x.max_acceleration_reverse, params_.linear.x.max_acceleration,
params_.linear.x.max_deceleration, params_.linear.x.max_deceleration_reverse,
params_.linear.x.min_jerk, params_.linear.x.max_jerk);

limiter_angular_ = std::make_unique<SpeedLimiter>(
params_.angular.z.min_velocity, params_.angular.z.max_velocity,
params_.angular.z.max_acceleration_reverse, params_.angular.z.max_acceleration,
params_.angular.z.max_deceleration, params_.angular.z.max_deceleration_reverse,
params_.angular.z.min_jerk, params_.angular.z.max_jerk);
Copy link
Contributor

@christophfroehlich christophfroehlich Jul 30, 2025

Choose a reason for hiding this comment

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

This method is part of the RT loop, we must not allocate memory here. Better leave the initial construction of the objects in the on_configure, but update the parameters (only if they changed, i.e., inside the if clause above).
To achieve this, we have to expose the control_toolbox::RateLimiter::set_params method in the diff_drive_controller::SpeedLimiter class.
https://github.com/ros-controls/control_toolbox/blob/c46e3c5b56d62c30e30e42d3658821fbf909dd3e/control_toolbox/include/control_toolbox/rate_limiter.hpp#L107-L132

Furthermore, we should change the rate_limiter class to throw the errors of the input checks before the member variables are set. So we can catch the errors in the diff_drive_controller::SpeedLimiter::set_params method, otherwise we have to reimplement the checks to avoid crashing the controller: ros-controls/control_toolbox#437

Copy link
Contributor

@christophfroehlich christophfroehlich left a comment

Choose a reason for hiding this comment

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

And please install pre-commit, so that it automatically checks for the rules (see the failing pre-commit jobs).

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants