-
Notifications
You must be signed in to change notification settings - Fork 333
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
base: master
Are you sure you want to change the base?
Scaled jtc #1191
Changes from all commits
d1fcba0
55c3bb0
79a8b7c
600ba71
c01b1ad
c003883
aa63e5d
821c88d
f7d0ae0
71ccb39
1fb38b8
6890d6e
b5a567d
908b539
1e66e44
7daf240
66abfd9
45fa036
5e9592b
42394b9
ba5fecb
4b2f18c
76e5cab
b22ce07
7e88744
d2130e0
915bfd3
90c6d45
77e78ce
0a3b974
09bea48
9658347
0dba992
a96dd54
d55fea7
9400838
777e5a9
62003f8
1f9bfb4
adc270f
0d08c38
35dbc4f
c56ce2b
b395104
b101360
21c9c4d
9d5c981
a2d319b
5d2b852
7844221
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,104 @@ | ||
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 | ||
: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. | ||
|
||
Scaling is done in such a way, that the time in the trajectory is virtually scaled. For example, if | ||
a controller runs with a cycle time of 100 Hz, each control cycle is 10 ms long. A speed scaling of | ||
0.5 means that in each time step the trajectory is moved forward by 5 ms instead. | ||
So, the beginning of the 3rd timestep is 15 ms instead of 30 ms in the trajectory. | ||
|
||
Command sampling is performed as in the unscaled case, with the timestep's start plus the **full** | ||
cycle time of 10 ms. The robot will scale down the motion command by 50% resulting in only half of | ||
the distance being executed, which is why the next control cycle will be started at the current | ||
start plus half of the step time. | ||
|
||
|
||
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 through the | ||
``~/speed_scaling_input`` topic directly: | ||
|
||
.. code:: console | ||
|
||
$ ros2 topic pub --qos-durability transient_local --once \ | ||
/joint_trajectory_controller/speed_scaling_input control_msgs/msg/SpeedScalingFactor "{factor: 0.5}" | ||
|
||
|
||
.. note:: | ||
The ``~/speed_scaling_input`` topic uses the QoS durability profile ``transient_local``. This | ||
means you can restart the controller while still having a publisher on that topic active. | ||
|
||
.. note:: | ||
The current implementation only works for position-based interfaces. | ||
|
||
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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? There was a problem hiding this comment. Choose a reason for hiding this commentThe 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. There was a problem hiding this comment. Choose a reason for hiding this commentThe 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 |
||
|
||
Effect on tolerances | ||
-------------------- | ||
|
||
When speed scaling is used while executing a trajectory, the tolerances configured for execution | ||
will be scaled, as well. | ||
|
||
Since commands are generated from the scaled trajectory time, **path errors** will also be compared | ||
to the scaled trajectory. | ||
|
||
The **goal time tolerance** also uses the virtual trajectory time. This means that a trajectory | ||
being executed with a constant scaling factor of 0.5 will take twice as long for execution than the | ||
``time_from_start`` value of the last trajectory point specifies. As long as the robot doesn't take | ||
longer than that the goal time tolerance is considered to be met. | ||
|
||
If an application relies on the actual execution time as set in the ``time_from_start`` fields, an | ||
external monitoring has to be wrapped around the trajectory execution action. |
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -116,12 +116,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()); | ||
|
@@ -132,16 +137,39 @@ JointTrajectoryController::state_interface_configuration() const | |
conf.names.push_back(joint_name + "/" + interface_type); | ||
} | ||
} | ||
if (!params_.speed_scaling_state_interface_name.empty()) | ||
{ | ||
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 (scaling_state_interface_.has_value()) | ||
{ | ||
scaling_factor_ = scaling_state_interface_->get().get_value(); | ||
} | ||
|
||
if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) | ||
{ | ||
return controller_interface::return_type::OK; | ||
} | ||
|
||
if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) | ||
{ | ||
if (scaling_command_interface_.has_value()) | ||
{ | ||
if (!scaling_command_interface_->get().set_value(scaling_factor_.load())) | ||
{ | ||
RCLCPP_ERROR( | ||
get_node()->get_logger(), | ||
"Could not set speed scaling factor through command interfaces."); | ||
} | ||
} | ||
} | ||
|
||
auto logger = this->get_node()->get_logger(); | ||
// update dynamic parameters | ||
if (param_listener_->is_old(params_)) | ||
|
@@ -200,18 +228,21 @@ controller_interface::return_type JointTrajectoryController::update( | |
} | ||
else | ||
{ | ||
traj_time_ += period; | ||
traj_time_ += period * scaling_factor_; | ||
} | ||
|
||
// Sample expected state from the trajectory | ||
traj_external_point_ptr_->sample( | ||
traj_time_, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr); | ||
state_desired_.time_from_start = traj_time_ - traj_external_point_ptr_->time_from_start(); | ||
|
||
// Sample setpoint for next control cycle | ||
const bool valid_point = traj_external_point_ptr_->sample( | ||
traj_time_ + update_period_, interpolation_method_, command_next_, start_segment_itr, | ||
end_segment_itr, false); | ||
|
||
state_current_.time_from_start = time - traj_external_point_ptr_->time_from_start(); | ||
|
||
if (valid_point) | ||
{ | ||
const rclcpp::Time traj_start = traj_external_point_ptr_->time_from_start(); | ||
|
@@ -329,7 +360,6 @@ controller_interface::return_type JointTrajectoryController::update( | |
auto feedback = std::make_shared<FollowJTrajAction::Feedback>(); | ||
feedback->header.stamp = time; | ||
feedback->joint_names = params_.joints; | ||
|
||
feedback->actual = state_current_; | ||
feedback->desired = state_desired_; | ||
feedback->error = state_error_; | ||
|
@@ -874,10 +904,45 @@ 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_) | ||
{ | ||
auto qos = rclcpp::SystemDefaultsQoS(); | ||
qos.transient_local(); | ||
scaling_factor_sub_ = get_node()->create_subscription<SpeedScalingMsg>( | ||
"~/speed_scaling_input", qos, | ||
[&](const SpeedScalingMsg & msg) { set_scaling_factor(msg.factor); }); | ||
RCLCPP_INFO( | ||
logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default); | ||
scaling_factor_ = 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_ = 1.0; | ||
} | ||
if (!params_.speed_scaling_state_interface_name.empty()) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Does it make sense to allow changing the scaling_factor via the topic and from the teach panel ? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It should be either topic or hardware, at least that was my intention. I'll revisit that to verify that that;s what I've implemented. Edit: It's in the |
||
{ | ||
RCLCPP_INFO( | ||
logger, "Using scaling state from the hardware from interface %s.", | ||
params_.speed_scaling_state_interface_name.c_str()); | ||
} | ||
else | ||
{ | ||
RCLCPP_INFO( | ||
get_node()->get_logger(), | ||
"No scaling interface set. This controller will not read speed scaling from the hardware."); | ||
} | ||
|
||
if (get_update_rate() == 0) | ||
{ | ||
throw std::runtime_error("Controller's update rate is set to 0. This should not happen!"); | ||
|
@@ -902,6 +967,34 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate( | |
// parse remaining parameters | ||
default_tolerances_ = get_segment_tolerances(logger, params_); | ||
|
||
// Set scaling interfaces | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This part has no test coverage |
||
if (!params_.speed_scaling_state_interface_name.empty()) | ||
{ | ||
auto it = std::find_if( | ||
state_interfaces_.begin(), state_interfaces_.end(), [&](auto & interface) | ||
{ return (interface.get_name() == params_.speed_scaling_state_interface_name); }); | ||
if (it != state_interfaces_.end()) | ||
{ | ||
scaling_state_interface_ = *it; | ||
} | ||
else | ||
{ | ||
RCLCPP_ERROR( | ||
logger, "Did not find speed scaling interface '%s' in state interfaces.", | ||
params_.speed_scaling_state_interface_name.c_str()); | ||
} | ||
} | ||
if (!params_.speed_scaling_command_interface_name.empty()) | ||
{ | ||
auto it = std::find_if( | ||
command_interfaces_.begin(), command_interfaces_.end(), [&](auto & interface) | ||
{ return (interface.get_name() == params_.speed_scaling_command_interface_name); }); | ||
if (it != command_interfaces_.end()) | ||
{ | ||
scaling_command_interface_ = *it; | ||
} | ||
} | ||
|
||
// order all joints in the storage | ||
for (const auto & interface : params_.command_interfaces) | ||
{ | ||
|
@@ -1105,6 +1198,7 @@ void JointTrajectoryController::publish_state( | |
{ | ||
state_publisher_->msg_.output = command_current_; | ||
} | ||
state_publisher_->msg_.speed_scaling_factor = scaling_factor_; | ||
|
||
state_publisher_->unlockAndPublish(); | ||
} | ||
|
@@ -1580,6 +1674,37 @@ void JointTrajectoryController::resize_joint_trajectory_point_command( | |
} | ||
} | ||
|
||
bool JointTrajectoryController::set_scaling_factor(const double scaling_factor) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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; | ||
} | ||
|
||
if (scaling_factor_ != scaling_factor_) | ||
{ | ||
RCLCPP_INFO( | ||
get_node()->get_logger().get_child("speed_scaling"), "New scaling factor will be %f", | ||
scaling_factor); | ||
} | ||
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_ = scaling_factor; | ||
} | ||
return true; | ||
} | ||
|
||
bool JointTrajectoryController::has_active_trajectory() const | ||
{ | ||
return traj_external_point_ptr_ != nullptr && traj_external_point_ptr_->has_trajectory_msg(); | ||
|
There was a problem hiding this comment.
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
There was a problem hiding this comment.
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.