Skip to content

Commit 4aea77a

Browse files
fmauchmamueluth
andcommitted
synchronization of scaling factor with hw optional, add service for setting
of scaling factor Co-authored-by: Manuel M <mamueluth@gmail.com>
1 parent 0904e7c commit 4aea77a

File tree

3 files changed

+64
-10
lines changed

3 files changed

+64
-10
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
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"
2728
#include "control_toolbox/pid.hpp"
2829
#include "controller_interface/controller_interface.hpp"
2930
#include "hardware_interface/types/hardware_interface_type_values.hpp"
@@ -311,8 +312,15 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
311312
void resize_joint_trajectory_point_command(
312313
trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
313314

315+
bool set_scaling_factor(
316+
control_msgs::srv::SetScalingFactor::Request::SharedPtr req,
317+
control_msgs::srv::SetScalingFactor::Response::SharedPtr resp);
318+
314319
urdf::Model model_;
315320

321+
realtime_tools::RealtimeBuffer<double> scaling_factor_rt_buff_;
322+
rclcpp::Service<control_msgs::srv::SetScalingFactor>::SharedPtr set_scaling_factor_srv_;
323+
316324
/**
317325
* @brief Assigns the values from a trajectory point interface to a joint interface.
318326
*

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 45 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -117,22 +117,32 @@ JointTrajectoryController::state_interface_configuration() const
117117
conf.names.push_back(joint_name + "/" + interface_type);
118118
}
119119
}
120-
conf.names.push_back(params_.speed_scaling_interface_name);
120+
if (params_.exchange_scaling_factor_with_hardware)
121+
{
122+
conf.names.push_back(params_.speed_scaling_interface_name);
123+
}
121124
return conf;
122125
}
123126

124127
controller_interface::return_type JointTrajectoryController::update(
125128
const rclcpp::Time & time, const rclcpp::Duration & period)
126129
{
127-
if (state_interfaces_.back().get_name() == params_.speed_scaling_interface_name)
130+
if (params_.exchange_scaling_factor_with_hardware)
128131
{
129-
scaling_factor_ = state_interfaces_.back().get_value();
132+
if (state_interfaces_.back().get_name() == params_.speed_scaling_interface_name)
133+
{
134+
scaling_factor_ = state_interfaces_.back().get_value();
135+
}
136+
else
137+
{
138+
RCLCPP_ERROR(
139+
get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.",
140+
params_.speed_scaling_interface_name.c_str());
141+
}
130142
}
131143
else
132144
{
133-
RCLCPP_ERROR(
134-
get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.",
135-
params_.speed_scaling_interface_name.c_str());
145+
scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT());
136146
}
137147

138148
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
@@ -468,8 +478,7 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto
468478
auto interface_has_values = [](const auto & joint_interface)
469479
{
470480
return std::find_if(
471-
joint_interface.begin(), joint_interface.end(),
472-
[](const auto & interface)
481+
joint_interface.begin(), joint_interface.end(), [](const auto & interface)
473482
{ return std::isnan(interface.get().get_value()); }) == joint_interface.end();
474483
};
475484

@@ -539,8 +548,7 @@ bool JointTrajectoryController::read_commands_from_command_interfaces(
539548
auto interface_has_values = [](const auto & joint_interface)
540549
{
541550
return std::find_if(
542-
joint_interface.begin(), joint_interface.end(),
543-
[](const auto & interface)
551+
joint_interface.begin(), joint_interface.end(), [](const auto & interface)
544552
{ return std::isnan(interface.get().get_value()); }) == joint_interface.end();
545553
};
546554

@@ -900,10 +908,19 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
900908
resize_joint_trajectory_point(state_error_, dof_);
901909
resize_joint_trajectory_point(last_commanded_state_, dof_);
902910

911+
// create services
903912
query_state_srv_ = get_node()->create_service<control_msgs::srv::QueryTrajectoryState>(
904913
std::string(get_node()->get_name()) + "/query_state",
905914
std::bind(&JointTrajectoryController::query_state_service, this, _1, _2));
906915

916+
set_scaling_factor_srv_ = get_node()->create_service<control_msgs::srv::SetScalingFactor>(
917+
"~/set_scaling_factor", std::bind(
918+
&JointTrajectoryController::set_scaling_factor, this,
919+
std::placeholders::_1, std::placeholders::_2));
920+
921+
// set scaling factor to low value default
922+
scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default);
923+
907924
return CallbackReturn::SUCCESS;
908925
}
909926

@@ -1600,6 +1617,24 @@ void JointTrajectoryController::resize_joint_trajectory_point_command(
16001617
}
16011618
}
16021619

1620+
bool JointTrajectoryController::set_scaling_factor(
1621+
control_msgs::srv::SetScalingFactor::Request::SharedPtr req,
1622+
control_msgs::srv::SetScalingFactor::Response::SharedPtr resp)
1623+
{
1624+
if (req->scaling_factor < 0 && req->scaling_factor > 1)
1625+
{
1626+
RCLCPP_WARN(
1627+
get_node()->get_logger(), "Scaling factor has to be in range [0, 1]. Ignoring input!");
1628+
resp->success = false;
1629+
return true;
1630+
}
1631+
1632+
RCLCPP_INFO(get_node()->get_logger(), "New scaling factor will be %f", req->scaling_factor);
1633+
scaling_factor_rt_buff_.writeFromNonRT(req->scaling_factor);
1634+
resp->success = true;
1635+
return true;
1636+
}
1637+
16031638
bool JointTrajectoryController::has_active_trajectory() const
16041639
{
16051640
return traj_external_point_ptr_ != nullptr && traj_external_point_ptr_->has_trajectory_msg();

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,17 @@ joint_trajectory_controller:
3939
"joint_trajectory_controller::state_interface_type_combinations": null,
4040
}
4141
}
42+
exchange_scaling_factor_with_hardware: {
43+
type: bool,
44+
default_value: false,
45+
description: "Flag that mark is hardware supports setting and reading of scaling factor.\n
46+
If set to 'true' corresponding command and state interfaces are created."
47+
}
48+
scaling_factor_initial_default: {
49+
type: double,
50+
default_value: 1.0,
51+
description: "The initial value of the scaling factor if not exchange with hardware takes place."
52+
}
4253
speed_scaling_interface_name: {
4354
type: string,
4455
default_value: "speed_scaling/speed_scaling_factor",

0 commit comments

Comments
 (0)