Skip to content

Commit

Permalink
Parameter loading fixup in diff_drive and gripper controllers (ros-co…
Browse files Browse the repository at this point in the history
…ntrols#385)

* Parameter loading fixup

* Lint
  • Loading branch information
AndyZe authored Jul 23, 2022
1 parent 59cf344 commit 001d896
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 4 deletions.
7 changes: 4 additions & 3 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,9 +77,10 @@ controller_interface::CallbackReturn DiffDriveController::on_init()
auto_declare<bool>("enable_odom_tf", odom_params_.enable_odom_tf);

auto_declare<double>("cmd_vel_timeout", cmd_vel_timeout_.count() / 1000.0);
auto_declare<bool>("publish_limited_velocity", publish_limited_velocity_);
publish_limited_velocity_ = auto_declare<bool>("publish_limited_velocity",
publish_limited_velocity_);
auto_declare<int>("velocity_rolling_window_size", 10);
auto_declare<bool>("use_stamped_vel", use_stamped_vel_);
use_stamped_vel_ = auto_declare<bool>("use_stamped_vel", use_stamped_vel_);

auto_declare<bool>("linear.x.has_velocity_limits", false);
auto_declare<bool>("linear.x.has_acceleration_limits", false);
Expand All @@ -100,7 +101,7 @@ controller_interface::CallbackReturn DiffDriveController::on_init()
auto_declare<double>("angular.z.min_acceleration", NAN);
auto_declare<double>("angular.z.max_jerk", NAN);
auto_declare<double>("angular.z.min_jerk", NAN);
auto_declare<double>("publish_rate", publish_rate_);
publish_rate_ = auto_declare<double>("publish_rate", publish_rate_);
}
catch (const std::exception & e)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ controller_interface::CallbackReturn GripperActionController<HardwareInterface>:
{
// with the lifecycle node being initialized, we can declare parameters
auto_declare<double>("action_monitor_rate", 20.0);
auto_declare<std::string>("joint", joint_name_);
joint_name_ = auto_declare<std::string>("joint", joint_name_);
auto_declare<double>("goal_tolerance", 0.01);
auto_declare<double>("max_effort", 0.0);
auto_declare<bool>("allow_stalling", false);
Expand Down

0 comments on commit 001d896

Please sign in to comment.