Skip to content

Commit 41aa16a

Browse files
Felix ExnerRobertWilbrandt
authored andcommitted
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 b0391e2 commit 41aa16a

File tree

3 files changed

+53
-5
lines changed

3 files changed

+53
-5
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,14 @@ using namespace std::chrono_literals; // NOLINT
5050
namespace joint_trajectory_controller
5151
{
5252

53+
struct TimeData
54+
{
55+
TimeData() : time(0.0), period(rclcpp::Duration::from_nanoseconds(0.0)), uptime(0.0) {}
56+
rclcpp::Time time;
57+
rclcpp::Duration period;
58+
rclcpp::Time uptime;
59+
};
60+
5361
class JointTrajectoryController : public controller_interface::ControllerInterface
5462
{
5563
public:
@@ -159,6 +167,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
159167
// reserved storage for result of the command when closed loop pid adapter is used
160168
std::vector<double> tmp_command_;
161169

170+
// Things around speed scaling
171+
double scaling_factor_{};
172+
realtime_tools::RealtimeBuffer<TimeData> time_data_;
173+
162174
// Timeout to consider commands old
163175
double cmd_timeout_;
164176
// True if holding position or repeating last trajectory point in case of success

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 36 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include <chrono>
1818
#include <functional>
19+
#include <iostream>
1920
#include <memory>
2021

2122
#include <string>
@@ -131,12 +132,24 @@ JointTrajectoryController::state_interface_configuration() const
131132
conf.names.push_back(joint_name + "/" + interface_type);
132133
}
133134
}
135+
conf.names.push_back(params_.speed_scaling_interface_name);
134136
return conf;
135137
}
136138

137139
controller_interface::return_type JointTrajectoryController::update(
138140
const rclcpp::Time & time, const rclcpp::Duration & period)
139141
{
142+
if (state_interfaces_.back().get_name() == params_.speed_scaling_interface_name)
143+
{
144+
scaling_factor_ = state_interfaces_.back().get_value();
145+
}
146+
else
147+
{
148+
RCLCPP_ERROR(
149+
get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.",
150+
params_.speed_scaling_interface_name.c_str());
151+
}
152+
140153
if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
141154
{
142155
return controller_interface::return_type::OK;
@@ -179,6 +192,16 @@ controller_interface::return_type JointTrajectoryController::update(
179192
// currently carrying out a trajectory
180193
if (has_active_trajectory())
181194
{
195+
// Adjust time with scaling factor
196+
TimeData time_data;
197+
time_data.time = time;
198+
rcl_duration_value_t t_period = (time_data.time - time_data_.readFromRT()->time).nanoseconds();
199+
time_data.period = rclcpp::Duration::from_nanoseconds(scaling_factor_ * t_period);
200+
time_data.uptime = time_data_.readFromRT()->uptime + time_data.period;
201+
rclcpp::Time traj_time =
202+
time_data_.readFromRT()->uptime + rclcpp::Duration::from_nanoseconds(t_period);
203+
time_data_.writeFromNonRT(time_data);
204+
182205
bool first_sample = false;
183206
// if sampling the first time, set the point before you sample
184207
if (!traj_external_point_ptr_->is_sampled_already())
@@ -187,19 +210,19 @@ controller_interface::return_type JointTrajectoryController::update(
187210
if (params_.open_loop_control)
188211
{
189212
traj_external_point_ptr_->set_point_before_trajectory_msg(
190-
time, last_commanded_state_, joints_angle_wraparound_);
213+
traj_time, last_commanded_state_, joints_angle_wraparound_);
191214
}
192215
else
193216
{
194217
traj_external_point_ptr_->set_point_before_trajectory_msg(
195-
time, state_current_, joints_angle_wraparound_);
218+
traj_time, state_current_, joints_angle_wraparound_);
196219
}
197220
}
198221

199222
// find segment for current timestamp
200223
TrajectoryPointConstIter start_segment_itr, end_segment_itr;
201224
const bool valid_point = traj_external_point_ptr_->sample(
202-
time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
225+
traj_time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
203226

204227
if (valid_point)
205228
{
@@ -460,7 +483,8 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto
460483
auto interface_has_values = [](const auto & joint_interface)
461484
{
462485
return std::find_if(
463-
joint_interface.begin(), joint_interface.end(), [](const auto & interface)
486+
joint_interface.begin(), joint_interface.end(),
487+
[](const auto & interface)
464488
{ return std::isnan(interface.get().get_value()); }) == joint_interface.end();
465489
};
466490

@@ -530,7 +554,8 @@ bool JointTrajectoryController::read_commands_from_command_interfaces(
530554
auto interface_has_values = [](const auto & joint_interface)
531555
{
532556
return std::find_if(
533-
joint_interface.begin(), joint_interface.end(), [](const auto & interface)
557+
joint_interface.begin(), joint_interface.end(),
558+
[](const auto & interface)
534559
{ return std::isnan(interface.get().get_value()); }) == joint_interface.end();
535560
};
536561

@@ -883,6 +908,12 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
883908

884909
// parse remaining parameters
885910
default_tolerances_ = get_segment_tolerances(logger, params_);
911+
// Setup time_data buffer used for scaling
912+
TimeData time_data;
913+
time_data.time = get_node()->now();
914+
time_data.period = rclcpp::Duration::from_nanoseconds(0);
915+
time_data.uptime = get_node()->now();
916+
time_data_.initRT(time_data);
886917

887918
// order all joints in the storage
888919
for (const auto & interface : params_.command_interfaces)

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)