@@ -914,10 +914,9 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
914914 !has_velocity_command_interface_ && !has_acceleration_command_interface_ &&
915915 !has_effort_command_interface_)
916916 {
917- set_scaling_factor_srv_ = get_node ()->create_service <control_msgs::srv::SetScalingFactor>(
918- " ~/set_scaling_factor" , std::bind (
919- &JointTrajectoryController::set_scaling_factor, this ,
920- std::placeholders::_1, std::placeholders::_2));
917+ scaling_factor_sub_ = get_node ()->create_subscription <std_msgs::msg::Float64>(
918+ " ~/speed_scaling_input" , rclcpp::SystemDefaultsQoS (),
919+ [&](const std_msgs::msg::Float64 & msg) { set_scaling_factor (msg.data );});
921920 RCLCPP_INFO (
922921 logger, " Setting initial scaling factor to %2f" , params_.scaling_factor_initial_default );
923922 scaling_factor_rt_buff_.writeFromNonRT (params_.scaling_factor_initial_default );
@@ -1626,19 +1625,16 @@ void JointTrajectoryController::resize_joint_trajectory_point_command(
16261625 }
16271626}
16281627
1629- bool JointTrajectoryController::set_scaling_factor (
1630- control_msgs::srv::SetScalingFactor::Request::SharedPtr req,
1631- control_msgs::srv::SetScalingFactor::Response::SharedPtr resp)
1628+ bool JointTrajectoryController::set_scaling_factor (const double scaling_factor)
16321629{
1633- if (req-> scaling_factor < 0 && req-> scaling_factor > 1 )
1630+ if (scaling_factor < 0 || scaling_factor > 1 )
16341631 {
16351632 RCLCPP_WARN (
16361633 get_node ()->get_logger (), " Scaling factor has to be in range [0, 1]. Ignoring input!" );
1637- resp->success = false ;
1638- return true ;
1634+ return false ;
16391635 }
16401636
1641- RCLCPP_INFO (get_node ()->get_logger (), " New scaling factor will be %f" , req-> scaling_factor );
1637+ RCLCPP_INFO (get_node ()->get_logger (), " New scaling factor will be %f" , scaling_factor);
16421638 if (params_.speed_scaling_command_interface_name .empty ())
16431639 {
16441640 if (!params_.speed_scaling_state_interface_name .empty ())
@@ -1649,7 +1645,7 @@ bool JointTrajectoryController::set_scaling_factor(
16491645 " This will likely get overwritten by the hardware again. If available, please also setup "
16501646 " the speed_scaling_command_interface_name" );
16511647 }
1652- scaling_factor_rt_buff_.writeFromNonRT (req-> scaling_factor );
1648+ scaling_factor_rt_buff_.writeFromNonRT (scaling_factor);
16531649 }
16541650 else
16551651 {
@@ -1659,12 +1655,11 @@ bool JointTrajectoryController::set_scaling_factor(
16591655 {
16601656 if (interface.get_name () == params_.speed_scaling_command_interface_name )
16611657 {
1662- interface.set_value (static_cast <double >(req-> scaling_factor ));
1658+ interface.set_value (static_cast <double >(scaling_factor));
16631659 }
16641660 }
16651661 }
16661662 }
1667- resp->success = true ;
16681663 return true ;
16691664}
16701665
0 commit comments