Skip to content

Commit 3ea1e40

Browse files
author
Lennart Nachtigall
committed
ported scaled jtc
move TimeData reset to on_activate run pre-commit Add goal time violated fix
1 parent b441ced commit 3ea1e40

File tree

3 files changed

+52
-4
lines changed

3 files changed

+52
-4
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@
4141
#include "realtime_tools/realtime_buffer.h"
4242
#include "realtime_tools/realtime_publisher.h"
4343
#include "realtime_tools/realtime_server_goal_handle.h"
44+
#include "std_msgs/msg/float64.hpp"
4445
#include "trajectory_msgs/msg/joint_trajectory.hpp"
4546
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
4647
#include "urdf/model.h"
@@ -287,6 +288,15 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
287288
const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
288289
std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response);
289290

291+
// TimeData struct used for trajectory scaling information
292+
struct TimeData
293+
{
294+
TimeData() : time(0.0), period(rclcpp::Duration::from_nanoseconds(0.0)), uptime(0.0) {}
295+
rclcpp::Time time;
296+
rclcpp::Duration period;
297+
rclcpp::Time uptime;
298+
};
299+
290300
private:
291301
void update_pids();
292302

@@ -301,6 +311,12 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
301311

302312
urdf::Model model_;
303313

314+
using ScalingFactorMsg = std_msgs::msg::Float64;
315+
double scaling_factor_{1.0};
316+
rclcpp::Subscription<ScalingFactorMsg>::SharedPtr scaling_factor_sub_;
317+
318+
TimeData time_data_;
319+
304320
/**
305321
* @brief Assigns the values from a trajectory point interface to a joint interface.
306322
*

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 30 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -163,6 +163,15 @@ controller_interface::return_type JointTrajectoryController::update(
163163
// currently carrying out a trajectory
164164
if (has_active_trajectory())
165165
{
166+
TimeData time_data;
167+
time_data.time = time;
168+
rcl_duration_value_t t_period = (time_data.time - time_data_.time).nanoseconds();
169+
time_data.period = rclcpp::Duration::from_nanoseconds(
170+
static_cast<rcutils_duration_value_t>(scaling_factor_ * static_cast<double>(t_period)));
171+
time_data.uptime = time_data_.uptime + time_data.period;
172+
rclcpp::Time traj_time = time_data_.uptime + rclcpp::Duration::from_nanoseconds(t_period);
173+
time_data_ = time_data;
174+
166175
bool first_sample = false;
167176
// if sampling the first time, set the point before you sample
168177
if (!traj_external_point_ptr_->is_sampled_already())
@@ -171,19 +180,19 @@ controller_interface::return_type JointTrajectoryController::update(
171180
if (params_.open_loop_control)
172181
{
173182
traj_external_point_ptr_->set_point_before_trajectory_msg(
174-
time, last_commanded_state_, joints_angle_wraparound_);
183+
traj_time, last_commanded_state_, joints_angle_wraparound_);
175184
}
176185
else
177186
{
178187
traj_external_point_ptr_->set_point_before_trajectory_msg(
179-
time, state_current_, joints_angle_wraparound_);
188+
traj_time, state_current_, joints_angle_wraparound_);
180189
}
181190
}
182191

183192
// find segment for current timestamp
184193
TrajectoryPointConstIter start_segment_itr, end_segment_itr;
185194
const bool valid_point = traj_external_point_ptr_->sample(
186-
time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
195+
traj_time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
187196

188197
if (valid_point)
189198
{
@@ -195,7 +204,7 @@ controller_interface::return_type JointTrajectoryController::update(
195204
// time_difference is
196205
// - negative until first point is reached
197206
// - counting from zero to time_from_start of next point
198-
double time_difference = time.seconds() - segment_time_from_start.seconds();
207+
const double time_difference = time_data.uptime.seconds() - segment_time_from_start.seconds();
199208
bool tolerance_violated_while_moving = false;
200209
bool outside_goal_tolerance = false;
201210
bool within_goal_time = true;
@@ -867,6 +876,16 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
867876
std::string(get_node()->get_name()) + "/query_state",
868877
std::bind(&JointTrajectoryController::query_state_service, this, _1, _2));
869878

879+
if (params_.speed_scaling_topic_name != "")
880+
{
881+
auto qos = rclcpp::QoS(10);
882+
qos.transient_local();
883+
884+
scaling_factor_sub_ = get_node()->create_subscription<ScalingFactorMsg>(
885+
params_.speed_scaling_topic_name, qos,
886+
// Explicitly allow factors > 1.0 which is really useful for simulation environments
887+
[&](const ScalingFactorMsg & msg) { scaling_factor_ = msg.data / 100.0; });
888+
}
870889
return CallbackReturn::SUCCESS;
871890
}
872891

@@ -960,6 +979,13 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
960979
cmd_timeout_ = 0.0;
961980
}
962981

982+
// Reset time_data for the trajectory scaling
983+
TimeData time_data;
984+
time_data.time = get_node()->now();
985+
time_data.period = rclcpp::Duration::from_nanoseconds(0);
986+
time_data.uptime = get_node()->now();
987+
time_data_ = time_data;
988+
963989
return CallbackReturn::SUCCESS;
964990
}
965991

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,12 @@ joint_trajectory_controller:
9595
``cmd_timeout`` must be greater than ``constraints.goal_time``, otherwise ignored.
9696
If zero, timeout is deactivated",
9797
}
98+
speed_scaling_topic_name: {
99+
type: string,
100+
default_value: "~/speed_scaling_factor",
101+
description: "Topic name for the speed scaling factor - set to an empty string in order to disable it"
102+
}
103+
98104
gains:
99105
__map_joints:
100106
p: {

0 commit comments

Comments
 (0)