Skip to content

Commit 4fb2e72

Browse files
author
Felix Exner
committed
Use a subscriber instead of a service
1 parent f175aca commit 4fb2e72

File tree

2 files changed

+17
-20
lines changed

2 files changed

+17
-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
@@ -24,7 +24,6 @@
2424
#include "control_msgs/action/follow_joint_trajectory.hpp"
2525
#include "control_msgs/msg/joint_trajectory_controller_state.hpp"
2626
#include "control_msgs/srv/query_trajectory_state.hpp"
27-
#include "control_msgs/srv/set_scaling_factor.hpp"
2827
#include "control_toolbox/pid.hpp"
2928
#include "controller_interface/controller_interface.hpp"
3029
#include "hardware_interface/types/hardware_interface_type_values.hpp"
@@ -46,6 +45,8 @@
4645
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
4746
#include "urdf/model.h"
4847

48+
#include "std_msgs/msg/float64.hpp"
49+
4950
// auto-generated by generate_parameter_library
5051
#include "joint_trajectory_controller_parameters.hpp"
5152

@@ -172,8 +173,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
172173
std::vector<double> tmp_command_;
173174

174175
// Things around speed scaling
175-
double scaling_factor_{};
176176
realtime_tools::RealtimeBuffer<TimeData> time_data_;
177+
double scaling_factor_{1.0};
177178

178179
// Timeout to consider commands old
179180
double cmd_timeout_;
@@ -312,14 +313,12 @@ 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
urdf::Model model_;
320319

321320
realtime_tools::RealtimeBuffer<double> scaling_factor_rt_buff_;
322-
rclcpp::Service<control_msgs::srv::SetScalingFactor>::SharedPtr set_scaling_factor_srv_;
321+
rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr scaling_factor_sub_;
323322

324323
/**
325324
* @brief Assigns the values from a trajectory point interface to a joint interface.

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 12 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -914,10 +914,12 @@ 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+
auto qos = rclcpp::QoS(1);
918+
qos.transient_local();
919+
920+
scaling_factor_sub_ = get_node()->create_subscription<std_msgs::msg::Float64>(
921+
"speed_scaling_input", qos,
922+
[&](const std_msgs::msg::Float64 & msg) { set_scaling_factor(msg.data);});
921923
RCLCPP_INFO(
922924
logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default);
923925
scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default);
@@ -1626,19 +1628,16 @@ void JointTrajectoryController::resize_joint_trajectory_point_command(
16261628
}
16271629
}
16281630

1629-
bool JointTrajectoryController::set_scaling_factor(
1630-
control_msgs::srv::SetScalingFactor::Request::SharedPtr req,
1631-
control_msgs::srv::SetScalingFactor::Response::SharedPtr resp)
1631+
bool JointTrajectoryController::set_scaling_factor(const double scaling_factor)
16321632
{
1633-
if (req->scaling_factor < 0 && req->scaling_factor > 1)
1633+
if (scaling_factor < 0 || scaling_factor > 1)
16341634
{
16351635
RCLCPP_WARN(
16361636
get_node()->get_logger(), "Scaling factor has to be in range [0, 1]. Ignoring input!");
1637-
resp->success = false;
1638-
return true;
1637+
return false;
16391638
}
16401639

1641-
RCLCPP_INFO(get_node()->get_logger(), "New scaling factor will be %f", req->scaling_factor);
1640+
RCLCPP_INFO(get_node()->get_logger(), "New scaling factor will be %f", scaling_factor);
16421641
if (params_.speed_scaling_command_interface_name.empty())
16431642
{
16441643
if (!params_.speed_scaling_state_interface_name.empty())
@@ -1649,7 +1648,7 @@ bool JointTrajectoryController::set_scaling_factor(
16491648
"This will likely get overwritten by the hardware again. If available, please also setup "
16501649
"the speed_scaling_command_interface_name");
16511650
}
1652-
scaling_factor_rt_buff_.writeFromNonRT(req->scaling_factor);
1651+
scaling_factor_rt_buff_.writeFromNonRT(scaling_factor);
16531652
}
16541653
else
16551654
{
@@ -1659,12 +1658,11 @@ bool JointTrajectoryController::set_scaling_factor(
16591658
{
16601659
if (interface.get_name() == params_.speed_scaling_command_interface_name)
16611660
{
1662-
interface.set_value(static_cast<double>(req->scaling_factor));
1661+
interface.set_value(static_cast<double>(scaling_factor));
16631662
}
16641663
}
16651664
}
16661665
}
1667-
resp->success = true;
16681666
return true;
16691667
}
16701668

0 commit comments

Comments
 (0)