Skip to content

Commit b76501a

Browse files
author
Felix Exner
committed
Do not advertise speed scaling service unless only position interface is
used The current implementation only works correctly when a position interface is used. When the hardware in fact slows down the robot (as UR does), also velocity interfaces should be scaled correctly, but that't rather an edge case right now.
1 parent 7597334 commit b76501a

File tree

1 file changed

+20
-7
lines changed

1 file changed

+20
-7
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 20 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -921,15 +921,28 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
921921
std::string(get_node()->get_name()) + "/query_state",
922922
std::bind(&JointTrajectoryController::query_state_service, this, _1, _2));
923923

924-
set_scaling_factor_srv_ = get_node()->create_service<control_msgs::srv::SetScalingFactor>(
925-
"~/set_scaling_factor", std::bind(
926-
&JointTrajectoryController::set_scaling_factor, this,
927-
std::placeholders::_1, std::placeholders::_2));
924+
if (
925+
!has_velocity_command_interface_ && !has_acceleration_command_interface_ &&
926+
!has_effort_command_interface_)
927+
{
928+
set_scaling_factor_srv_ = get_node()->create_service<control_msgs::srv::SetScalingFactor>(
929+
"~/set_scaling_factor", std::bind(
930+
&JointTrajectoryController::set_scaling_factor, this,
931+
std::placeholders::_1, std::placeholders::_2));
932+
RCLCPP_INFO(
933+
logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default);
934+
scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default);
935+
}
936+
else
937+
{
938+
RCLCPP_WARN(
939+
logger,
940+
"Speed scaling is currently only supported for position interfaces. If you want to make use "
941+
"of speed scaling, please only use a position interface when configuring this controller.");
942+
scaling_factor_rt_buff_.writeFromNonRT(1.0);
943+
}
928944

929945
// set scaling factor to low value default
930-
RCLCPP_INFO(
931-
logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default);
932-
scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default);
933946

934947
return CallbackReturn::SUCCESS;
935948
}

0 commit comments

Comments
 (0)