Skip to content

Commit 2db6392

Browse files
author
Felix Exner
committed
Add scaling factor to JTC
This adds a scaling factor between 0 and 1 to the JTC so that the trajectory time inside the controller is extended respectively. A value of 0.5 means that trajectory execution will take twice as long as the trajectory states. The scaling factor itself is read from the hardware for now.
1 parent 26a130b commit 2db6392

File tree

3 files changed

+47
-3
lines changed

3 files changed

+47
-3
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,16 @@ namespace joint_trajectory_controller
6464
{
6565
class Trajectory;
6666

67+
struct TimeData
68+
{
69+
TimeData() : time(0.0), period(rclcpp::Duration::from_nanoseconds(0.0)), uptime(0.0)
70+
{
71+
}
72+
rclcpp::Time time;
73+
rclcpp::Duration period;
74+
rclcpp::Time uptime;
75+
};
76+
6777
class JointTrajectoryController : public controller_interface::ControllerInterface
6878
{
6979
public:
@@ -174,6 +184,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
174184
// reserved storage for result of the command when closed loop pid adapter is used
175185
std::vector<double> tmp_command_;
176186

187+
// Things around speed scaling
188+
double scaling_factor_{};
189+
realtime_tools::RealtimeBuffer<TimeData> time_data_;
190+
177191
// Timeout to consider commands old
178192
double cmd_timeout_;
179193
// Are we holding position?

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 28 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include <stddef.h>
1818
#include <chrono>
1919
#include <functional>
20+
#include <iostream>
2021
#include <memory>
2122
#include <ostream>
2223
#include <ratio>
@@ -114,12 +115,20 @@ JointTrajectoryController::state_interface_configuration() const
114115
conf.names.push_back(joint_name + "/" + interface_type);
115116
}
116117
}
118+
conf.names.push_back(params_.speed_scaling_interface_name);
117119
return conf;
118120
}
119121

120122
controller_interface::return_type JointTrajectoryController::update(
121123
const rclcpp::Time & time, const rclcpp::Duration & period)
122124
{
125+
if (state_interfaces_.back().get_name() == params_.speed_scaling_interface_name) {
126+
scaling_factor_ = state_interfaces_.back().get_value();
127+
} else {
128+
RCLCPP_ERROR(get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.",
129+
params_.speed_scaling_interface_name.c_str());
130+
}
131+
123132
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
124133
{
125134
return controller_interface::return_type::OK;
@@ -189,25 +198,34 @@ controller_interface::return_type JointTrajectoryController::update(
189198
// currently carrying out a trajectory
190199
if (has_active_trajectory())
191200
{
201+
// Adjust time with scaling factor
202+
TimeData time_data;
203+
time_data.time = time;
204+
rcl_duration_value_t t_period = (time_data.time - time_data_.readFromRT()->time).nanoseconds();
205+
time_data.period = rclcpp::Duration::from_nanoseconds(scaling_factor_ * t_period);
206+
time_data.uptime = time_data_.readFromRT()->uptime + time_data.period;
207+
rclcpp::Time traj_time = time_data_.readFromRT()->uptime + rclcpp::Duration::from_nanoseconds(t_period);
208+
time_data_.writeFromNonRT(time_data);
209+
192210
bool first_sample = false;
193211
// if sampling the first time, set the point before you sample
194212
if (!traj_external_point_ptr_->is_sampled_already())
195213
{
196214
first_sample = true;
197215
if (params_.open_loop_control)
198216
{
199-
traj_external_point_ptr_->set_point_before_trajectory_msg(time, last_commanded_state_);
217+
traj_external_point_ptr_->set_point_before_trajectory_msg(traj_time, last_commanded_state_);
200218
}
201219
else
202220
{
203-
traj_external_point_ptr_->set_point_before_trajectory_msg(time, state_current_);
221+
traj_external_point_ptr_->set_point_before_trajectory_msg(traj_time, state_current_);
204222
}
205223
}
206224

207225
// find segment for current timestamp
208226
TrajectoryPointConstIter start_segment_itr, end_segment_itr;
209227
const bool valid_point = traj_external_point_ptr_->sample(
210-
time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
228+
traj_time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
211229

212230
if (valid_point)
213231
{
@@ -934,6 +952,13 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
934952
controller_interface::CallbackReturn JointTrajectoryController::on_activate(
935953
const rclcpp_lifecycle::State &)
936954
{
955+
// Setup time_data buffer used for scaling
956+
TimeData time_data;
957+
time_data.time = get_node()->now();
958+
time_data.period = rclcpp::Duration::from_nanoseconds(0);
959+
time_data.uptime = get_node()->now();
960+
time_data_.initRT(time_data);
961+
937962
// order all joints in the storage
938963
for (const auto & interface : params_.command_interfaces)
939964
{

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,11 @@ joint_trajectory_controller:
3939
"joint_trajectory_controller::state_interface_type_combinations": null,
4040
}
4141
}
42+
speed_scaling_interface_name: {
43+
type: string,
44+
default_value: "speed_scaling/speed_scaling_factor",
45+
description: "Fully qualified name of the speed scaling interface name"
46+
}
4247
allow_partial_joints_goal: {
4348
type: bool,
4449
default_value: false,

0 commit comments

Comments
 (0)