Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Scaled jtc #1191

Open
wants to merge 50 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 21 commits
Commits
Show all changes
50 commits
Select commit Hold shift + click to select a range
d1fcba0
Add scaling factor to JTC
fmauch Oct 4, 2023
55c3bb0
use reset+initRT due to missing writeFromRT
fmauch Oct 10, 2023
79a8b7c
Reformat scaling the time period
fmauch Mar 21, 2024
600ba71
synchronization of scaling factor with hw optional, add service for s…
fmauch Mar 22, 2024
c01b1ad
Improve scaling exchange with hardware
fmauch Mar 27, 2024
c003883
Check command interface name when setting speed scaling
fmauch Apr 3, 2024
aa63e5d
Update code formatting
fmauch Apr 3, 2024
821c88d
Do not advertise speed scaling service unless only position interface is
fmauch Apr 7, 2024
f7d0ae0
WIP: Adding documentation about speed scaling
fmauch Apr 7, 2024
71ccb39
Use a subscriber instead of a service
fmauch Jul 3, 2024
1fb38b8
Do not put the time_data_ into a RealtimeBuffer
fmauch Jul 3, 2024
6890d6e
Fix goal time violated
Jul 3, 2024
b5a567d
Merge remote-tracking branch 'origin/master' into scaled_jtc
fmauch Jul 3, 2024
908b539
Use custom message to subscribe speed scaling
fmauch Jul 3, 2024
1e66e44
Add scaling factor to controller state
fmauch Jul 3, 2024
7daf240
Code formatting
fmauch Jul 3, 2024
66abfd9
Allow scaling factors greater than 1
fmauch Jul 3, 2024
45fa036
Add parameter validator for default scaling factor
fmauch Jul 3, 2024
5e9592b
More formatting...
fmauch Jul 3, 2024
42394b9
Remove unnecessary iostream include
fmauch Jul 4, 2024
ba5fecb
REVERT_ME: Use dev branch for control_msgs
fmauch Jul 4, 2024
4b2f18c
Write back scaling factor to buffer when updated from hardware
fmauch Jul 4, 2024
76e5cab
Remove additional time_data structure in update method
fmauch Jul 4, 2024
b22ce07
Use std::atomic for scaling factor buff
fmauch Jul 4, 2024
7e88744
Use transient_local for the speed scaling topic subscriber
fmauch Jul 4, 2024
d2130e0
Added documentation on tolerance effects
fmauch Jul 5, 2024
915bfd3
Added a short explanation of scaling
fmauch Jul 5, 2024
90c6d45
Use a ordering-safe reference for scaling command and state interfaces
fmauch Jul 8, 2024
77e78ce
Merge branch 'master' into scaled_jtc
fmauch Jul 23, 2024
0a3b974
REVERT_ME Use my version of control_msgs
fmauch Jul 23, 2024
09bea48
Use period directly instead of calculating an own period
fmauch Jul 23, 2024
9658347
Merge branch 'master' into scaled_jtc
fmauch Aug 8, 2024
0dba992
Set update rate in testing controller
fmauch Aug 8, 2024
a96dd54
Tests: Call controller.configure() instead of controller.get_node().c…
fmauch Aug 28, 2024
d55fea7
Sample trajectory at point t+dT
fmauch Sep 12, 2024
9400838
Update trajectory_controller_tests
fmauch Oct 7, 2024
777e5a9
Merge branch 'master' into jtc_tdt
fmauch Oct 8, 2024
62003f8
Fix period calculation in trajectory_actions test
fmauch Oct 13, 2024
1f9bfb4
Sample trajectory based on the sum of periods instead of the absolute…
fmauch Oct 13, 2024
adc270f
Merge branch 'jtc_sum_periods' into scaled_jtc
fmauch Oct 13, 2024
0d08c38
Cleanup some logging
fmauch Oct 14, 2024
35dbc4f
Merge remote-tracking branch 'origin/master' into scaled_jtc_merged
fmauch Dec 1, 2024
c56ce2b
Add test for scaled trajectory execution
fmauch Dec 1, 2024
b395104
Merge remote-tracking branch 'origin/master' into scaled_jtc
fmauch Dec 3, 2024
b101360
Use master branch of control_msgs repo
christophfroehlich Dec 3, 2024
21c9c4d
Apply suggestions from code review
fmauch Dec 4, 2024
9d5c981
Update tolerances documentation
fmauch Dec 4, 2024
a2d319b
Only log set scaling factor if it is changed
fmauch Dec 4, 2024
5d2b852
Remove duplicate reading period from parameter
fmauch Dec 4, 2024
7844221
Make trajectory test use tolerances
fmauch Dec 4, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
75 changes: 75 additions & 0 deletions joint_trajectory_controller/doc/speed_scaling.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
Speed scaling
=============

The ``joint_trajectory_controller`` (JTC) supports dynamically scaling its trajectory execution speed.
That means, when specifying a scaling factor :math:`{f}` of less than 1, execution will proceed only
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is it possible to specify a value > 1 for simulation purposes ? We are using this quite a lot in our setup.
What would the maximum rate be? I saw the limit with the old implementation at 2.5

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, it can be greater than 1. I haven't investigated a limit, though.

:math:`{f \cdot \Delta_t}` per control step where :math:`{\Delta_t}` is the controller's cycle time.

Methods of speed scaling
------------------------

Generally, the speed scaling feature has two separate scaling approaches in mind: On-Robot scaling
and On-Controller scaling. They are both conceptually different and to correctly configure speed
scaling it is important to understand the differences.

On-Robot speed scaling
~~~~~~~~~~~~~~~~~~~~~~

This scaling method is intended for robots that provide a scaling feature directly on the robot's
teach pendant and / or through a safety feature. One example of such robots are the `Universal
Robots manipulators <https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver>`_.

For the scope of this documentation a user-defined scaling and a safety-limited scaling will be
treated the same resulting in a "hardware scaling factor".

In this setup, the hardware will treat the command sent from the ROS controller (e.g. Reach joint
configuration :math:`{\theta}` within :math:`{\Delta_t}` seconds.). This effectively means that the
robot will only make half of the way towards the target configuration when a scaling factor of 0.5
is given (neglectling acceleration and deceleration influcences during this time period).

The following plot shows trajectory execution (for one joint) with a hardware-scaled execution and
a controller that is **not** aware of speed scaling:

.. image:: traj_without_speed_scaling.png
:alt: Trajectory with a hardware-scaled-down execution with a non-scaled controller

The graph shows a trajectory with one joint being moved to a target point and back to its starting
point. As the joint's speed is limited to a very low setting on the teach pendant, speed scaling
(black line) activates and limits the joint speed (green line). As a result, the target trajectory
(light blue) doesn't get executed by the robot, but instead the pink trajectory is executed. The
vertical distance between the light blue line and the pink line is the path error in each control
cycle. We can see that the path deviation gets above 300 degrees at some point and the target point
at -6 radians never gets reached.

With the scaled version of the trajectory controller the example motion shown in the previous diagram becomes:

.. image:: traj_with_speed_scaling.png
:alt: Trajectory with a hardware-scaled-down execution with a scaled controller

The deviation between trajectory interpolation on the ROS side and actual robot execution stays
minimal and the robot reaches the intermediate setpoint instead of returning "too early" as in the
example above.

.. todo:: Describe method behind this scaling approach.


On-Controller speed scaling
~~~~~~~~~~~~~~~~~~~~~~~~~~~

Conceptionally, with this scaling the robot hardware isn't aware of any scaling happening. The JTC
generates commands to be sent to the robot that are already scaled down accordingly, so they can be
directly executed by the robot.

Since the hardware isn't aware of speed scaling, the speed-scaling related command and state
interfaces should not be specified and the scaling factor will be set by the ``setSpeedScaling``
service directly.

.. note::
The current implementation only works for position-based interfaces.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Perhaps I am too tired after the ROScon. But could it be that it doesn't become 100% clear how to select a specfic mode?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What do you mean by "how to select a specific mode"? The current implementation will simply not do speed scaling when any other interface than position is configured for the controller.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If I just read the documentation I would think:

a) There are multiple modes I can choose from with the hint that on-robot scaling probably produces the better results
b) If there are multiple modes I would think: Ok somehow I have to tell the JTC to select which mode.


Goal time tolerances
--------------------

.. todo::
What happens to goal time tolerances if we scale down a trajectory?
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
1 change: 1 addition & 0 deletions joint_trajectory_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -206,6 +206,7 @@ Further information
:titlesonly:

Trajectory Representation <trajectory.rst>
Speed scaling <speed_scaling.rst>
joint_trajectory_controller Parameters <parameters.rst>
rqt_joint_trajectory_controller <../../rqt_joint_trajectory_controller/doc/userdoc.rst>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@

#include "control_msgs/action/follow_joint_trajectory.hpp"
#include "control_msgs/msg/joint_trajectory_controller_state.hpp"
#include "control_msgs/msg/speed_scaling_factor.hpp"
#include "control_msgs/srv/query_trajectory_state.hpp"
#include "control_toolbox/pid.hpp"
#include "controller_interface/controller_interface.hpp"
Expand Down Expand Up @@ -53,6 +54,14 @@ using namespace std::chrono_literals; // NOLINT
namespace joint_trajectory_controller
{

struct TimeData
{
TimeData() : time(0.0), period(rclcpp::Duration::from_nanoseconds(0.0)), uptime(0.0) {}
rclcpp::Time time;
rclcpp::Duration period;
rclcpp::Time uptime;
};

class JointTrajectoryController : public controller_interface::ControllerInterface
{
public:
Expand Down Expand Up @@ -162,6 +171,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
// reserved storage for result of the command when closed loop pid adapter is used
std::vector<double> tmp_command_;

// Things around speed scaling
double scaling_factor_{1.0};
TimeData time_data_;

// Timeout to consider commands old
double cmd_timeout_;
// True if holding position or repeating last trajectory point in case of success
Expand Down Expand Up @@ -302,8 +315,14 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
void resize_joint_trajectory_point_command(
trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);

bool set_scaling_factor(const double scaling_factor);

urdf::Model model_;

realtime_tools::RealtimeBuffer<double> scaling_factor_rt_buff_;
fmauch marked this conversation as resolved.
Show resolved Hide resolved
using SpeedScalingMsg = control_msgs::msg::SpeedScalingFactor;
rclcpp::Subscription<SpeedScalingMsg>::SharedPtr scaling_factor_sub_;

/**
* @brief Assigns the values from a trajectory point interface to a joint interface.
*
Expand Down
115 changes: 111 additions & 4 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,12 +100,17 @@ JointTrajectoryController::command_interface_configuration() const
conf.names.push_back(joint_name + "/" + interface_type);
}
}
if (!params_.speed_scaling_command_interface_name.empty())
{
conf.names.push_back(params_.speed_scaling_command_interface_name);
}
return conf;
}

controller_interface::InterfaceConfiguration
JointTrajectoryController::state_interface_configuration() const
{
const auto logger = get_node()->get_logger();
controller_interface::InterfaceConfiguration conf;
conf.type = controller_interface::interface_configuration_type::INDIVIDUAL;
conf.names.reserve(dof_ * params_.state_interfaces.size());
Expand All @@ -116,12 +121,37 @@ JointTrajectoryController::state_interface_configuration() const
conf.names.push_back(joint_name + "/" + interface_type);
}
}
if (!params_.speed_scaling_state_interface_name.empty())
{
RCLCPP_INFO(
logger, "Using scaling state from the hardware from interface %s.",
params_.speed_scaling_state_interface_name.c_str());
conf.names.push_back(params_.speed_scaling_state_interface_name);
}
return conf;
}

controller_interface::return_type JointTrajectoryController::update(
const rclcpp::Time & time, const rclcpp::Duration & period)
{
if (params_.speed_scaling_state_interface_name.empty())
{
scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT());
}
else
{
if (state_interfaces_.back().get_name() == params_.speed_scaling_state_interface_name)
fmauch marked this conversation as resolved.
Show resolved Hide resolved
{
scaling_factor_ = state_interfaces_.back().get_value();
}
else
{
RCLCPP_ERROR(
get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.",
params_.speed_scaling_state_interface_name.c_str());
}
}

if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
{
return controller_interface::return_type::OK;
Expand Down Expand Up @@ -164,6 +194,15 @@ controller_interface::return_type JointTrajectoryController::update(
// currently carrying out a trajectory
if (has_active_trajectory())
{
// Adjust time with scaling factor
TimeData time_data;
time_data.time = time;
rcl_duration_value_t t_period = (time_data.time - time_data_.time).nanoseconds();
time_data.period = rclcpp::Duration::from_nanoseconds(t_period) * scaling_factor_;
time_data.uptime = time_data_.uptime + time_data.period;
rclcpp::Time traj_time = time_data_.uptime + rclcpp::Duration::from_nanoseconds(t_period);
time_data_ = time_data;

bool first_sample = false;
// if sampling the first time, set the point before you sample
if (!traj_external_point_ptr_->is_sampled_already())
Expand All @@ -172,19 +211,19 @@ controller_interface::return_type JointTrajectoryController::update(
if (params_.open_loop_control)
{
traj_external_point_ptr_->set_point_before_trajectory_msg(
time, last_commanded_state_, joints_angle_wraparound_);
traj_time, last_commanded_state_, joints_angle_wraparound_);
}
else
{
traj_external_point_ptr_->set_point_before_trajectory_msg(
time, state_current_, joints_angle_wraparound_);
traj_time, state_current_, joints_angle_wraparound_);
}
}

// find segment for current timestamp
TrajectoryPointConstIter start_segment_itr, end_segment_itr;
const bool valid_point = traj_external_point_ptr_->sample(
time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
traj_time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);

if (valid_point)
{
Expand All @@ -196,7 +235,7 @@ controller_interface::return_type JointTrajectoryController::update(
// time_difference is
// - negative until first point is reached
// - counting from zero to time_from_start of next point
double time_difference = time.seconds() - segment_time_from_start.seconds();
const double time_difference = time_data.uptime.seconds() - segment_time_from_start.seconds();
bool tolerance_violated_while_moving = false;
bool outside_goal_tolerance = false;
bool within_goal_time = true;
Expand Down Expand Up @@ -866,10 +905,33 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
resize_joint_trajectory_point(state_error_, dof_);
resize_joint_trajectory_point(last_commanded_state_, dof_);

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

if (
!has_velocity_command_interface_ && !has_acceleration_command_interface_ &&
!has_effort_command_interface_)
{
scaling_factor_sub_ = get_node()->create_subscription<SpeedScalingMsg>(
"~/speed_scaling_input", rclcpp::SystemDefaultsQoS(),
fmauch marked this conversation as resolved.
Show resolved Hide resolved
[&](const SpeedScalingMsg & msg) { set_scaling_factor(msg.factor); });
RCLCPP_INFO(
logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default);
scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default);
}
else
{
RCLCPP_WARN(
logger,
"Speed scaling is currently only supported for position interfaces. If you want to make use "
"of speed scaling, please only use a position interface when configuring this controller.");
scaling_factor_rt_buff_.writeFromNonRT(1.0);
}

// set scaling factor to low value default

return CallbackReturn::SUCCESS;
}

Expand All @@ -886,6 +948,11 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(

// parse remaining parameters
default_tolerances_ = get_segment_tolerances(logger, params_);
// Setup time_data buffer used for scaling
TimeData time_data;
time_data_.time = get_node()->now();
time_data_.period = rclcpp::Duration::from_nanoseconds(0);
time_data_.uptime = get_node()->now();

// order all joints in the storage
for (const auto & interface : params_.command_interfaces)
Expand Down Expand Up @@ -1088,6 +1155,7 @@ void JointTrajectoryController::publish_state(
{
state_publisher_->msg_.output = command_current_;
}
state_publisher_->msg_.speed_scaling_factor = *(scaling_factor_rt_buff_.readFromRT());

state_publisher_->unlockAndPublish();
}
Expand Down Expand Up @@ -1563,6 +1631,45 @@ void JointTrajectoryController::resize_joint_trajectory_point_command(
}
}

bool JointTrajectoryController::set_scaling_factor(const double scaling_factor)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This method has no test coverage

{
if (scaling_factor < 0)
{
RCLCPP_WARN(
get_node()->get_logger(),
"Scaling factor has to be greater or equal to 0.0 - Ignoring input!");
return false;
}

RCLCPP_INFO(get_node()->get_logger(), "New scaling factor will be %f", scaling_factor);
fmauch marked this conversation as resolved.
Show resolved Hide resolved
if (params_.speed_scaling_command_interface_name.empty())
{
if (!params_.speed_scaling_state_interface_name.empty())
{
RCLCPP_WARN(
get_node()->get_logger(),
"Setting the scaling factor while only one-way communication with the hardware is setup. "
"This will likely get overwritten by the hardware again. If available, please also setup "
"the speed_scaling_command_interface_name");
}
scaling_factor_rt_buff_.writeFromNonRT(scaling_factor);
}
else
{
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
fmauch marked this conversation as resolved.
Show resolved Hide resolved
{
for (auto & interface : command_interfaces_)
{
if (interface.get_name() == params_.speed_scaling_command_interface_name)
{
interface.set_value(static_cast<double>(scaling_factor));
}
}
}
}
return true;
}

bool JointTrajectoryController::has_active_trajectory() const
{
return traj_external_point_ptr_ != nullptr && traj_external_point_ptr_->has_trajectory_msg();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,26 @@ joint_trajectory_controller:
"joint_trajectory_controller::state_interface_type_combinations": null,
}
}
scaling_factor_initial_default: {
type: double,
default_value: 1.0,
fmauch marked this conversation as resolved.
Show resolved Hide resolved
description: "The initial value of the scaling factor if not exchange with hardware takes place.",
fmauch marked this conversation as resolved.
Show resolved Hide resolved
validation: {
gt_eq<>: 0.0,
}
}
speed_scaling_state_interface_name: {
type: string,
default_value: "",
read_only: true,
description: "Fully qualified name of the speed scaling state interface name"
}
speed_scaling_command_interface_name: {
type: string,
default_value: "",
read_only: true,
description: "Command interface name used for setting the speed scaling factor on the hardware."
}
allow_partial_joints_goal: {
type: bool,
default_value: false,
Expand Down
5 changes: 5 additions & 0 deletions ros2_controllers-not-released.jazzy.repos
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,8 @@ repositories:
type: git
url: https://github.com/picknikrobotics/generate_parameter_library.git
version: main

control_msgs:
type: git
url: https://github.com/fmauch/control_msgs.git
version: scaled_jtc
christophfroehlich marked this conversation as resolved.
Show resolved Hide resolved
5 changes: 5 additions & 0 deletions ros2_controllers-not-released.rolling.repos
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,8 @@ repositories:
type: git
url: https://github.com/picknikrobotics/generate_parameter_library.git
version: main

control_msgs:
type: git
url: https://github.com/fmauch/control_msgs.git
version: scaled_jtc
christophfroehlich marked this conversation as resolved.
Show resolved Hide resolved
Loading