We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
There was an error while loading. Please reload this page.
1 parent 6792f6f commit e8e0fdcCopy full SHA for e8e0fdc
joint_trajectory_controller/src/joint_trajectory_controller.cpp
@@ -1652,8 +1652,13 @@ bool JointTrajectoryController::set_scaling_factor(
1652
{
1653
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
1654
1655
- // TODO(Felix): Use proper adressing here.
1656
- command_interfaces_.back().set_value(static_cast<double>(req->scaling_factor));
+ for (auto & interface : command_interfaces_)
+ {
1657
+ if (interface.get_name() == params_.speed_scaling_command_interface_name)
1658
1659
+ interface.set_value(static_cast<double>(req->scaling_factor));
1660
+ }
1661
1662
}
1663
1664
resp->success = true;
0 commit comments