Skip to content

Commit c5ec03c

Browse files
Felix ExnerRobertWilbrandt
authored andcommitted
Use a subscriber instead of a service
1 parent bba5b36 commit c5ec03c

File tree

2 files changed

+14
-20
lines changed

2 files changed

+14
-20
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,6 @@
2323
#include "control_msgs/action/follow_joint_trajectory.hpp"
2424
#include "control_msgs/msg/joint_trajectory_controller_state.hpp"
2525
#include "control_msgs/srv/query_trajectory_state.hpp"
26-
#include "control_msgs/srv/set_scaling_factor.hpp"
2726
#include "control_toolbox/pid.hpp"
2827
#include "controller_interface/controller_interface.hpp"
2928
#include "hardware_interface/types/hardware_interface_type_values.hpp"
@@ -43,6 +42,8 @@
4342
#include "trajectory_msgs/msg/joint_trajectory.hpp"
4443
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
4544

45+
#include "std_msgs/msg/float64.hpp"
46+
4647
// auto-generated by generate_parameter_library
4748
#include "joint_trajectory_controller_parameters.hpp"
4849

@@ -169,8 +170,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
169170
std::vector<double> tmp_command_;
170171

171172
// Things around speed scaling
172-
double scaling_factor_{};
173173
realtime_tools::RealtimeBuffer<TimeData> time_data_;
174+
double scaling_factor_{1.0};
174175

175176
// Timeout to consider commands old
176177
double cmd_timeout_;
@@ -312,12 +313,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
312313
void resize_joint_trajectory_point_command(
313314
trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
314315

315-
bool set_scaling_factor(
316-
control_msgs::srv::SetScalingFactor::Request::SharedPtr req,
317-
control_msgs::srv::SetScalingFactor::Response::SharedPtr resp);
316+
bool set_scaling_factor(const double scaling_factor);
318317

319318
realtime_tools::RealtimeBuffer<double> scaling_factor_rt_buff_;
320-
rclcpp::Service<control_msgs::srv::SetScalingFactor>::SharedPtr set_scaling_factor_srv_;
319+
rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr scaling_factor_sub_;
321320
/**
322321
* @brief Assigns the values from a trajectory point interface to a joint interface.
323322
*

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 9 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -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);
@@ -1634,19 +1633,16 @@ void JointTrajectoryController::resize_joint_trajectory_point_command(
16341633
}
16351634
}
16361635

1637-
bool JointTrajectoryController::set_scaling_factor(
1638-
control_msgs::srv::SetScalingFactor::Request::SharedPtr req,
1639-
control_msgs::srv::SetScalingFactor::Response::SharedPtr resp)
1636+
bool JointTrajectoryController::set_scaling_factor(const double scaling_factor)
16401637
{
1641-
if (req->scaling_factor < 0 && req->scaling_factor > 1)
1638+
if (scaling_factor < 0 || scaling_factor > 1)
16421639
{
16431640
RCLCPP_WARN(
16441641
get_node()->get_logger(), "Scaling factor has to be in range [0, 1]. Ignoring input!");
1645-
resp->success = false;
1646-
return true;
1642+
return false;
16471643
}
16481644

1649-
RCLCPP_INFO(get_node()->get_logger(), "New scaling factor will be %f", req->scaling_factor);
1645+
RCLCPP_INFO(get_node()->get_logger(), "New scaling factor will be %f", scaling_factor);
16501646
if (params_.speed_scaling_command_interface_name.empty())
16511647
{
16521648
if (!params_.speed_scaling_state_interface_name.empty())
@@ -1657,7 +1653,7 @@ bool JointTrajectoryController::set_scaling_factor(
16571653
"This will likely get overwritten by the hardware again. If available, please also setup "
16581654
"the speed_scaling_command_interface_name");
16591655
}
1660-
scaling_factor_rt_buff_.writeFromNonRT(req->scaling_factor);
1656+
scaling_factor_rt_buff_.writeFromNonRT(scaling_factor);
16611657
}
16621658
else
16631659
{
@@ -1667,12 +1663,11 @@ bool JointTrajectoryController::set_scaling_factor(
16671663
{
16681664
if (interface.get_name() == params_.speed_scaling_command_interface_name)
16691665
{
1670-
interface.set_value(static_cast<double>(req->scaling_factor));
1666+
interface.set_value(static_cast<double>(scaling_factor));
16711667
}
16721668
}
16731669
}
16741670
}
1675-
resp->success = true;
16761671
return true;
16771672
}
16781673

0 commit comments

Comments
 (0)