Skip to content

Commit 1bd6870

Browse files
authored
[JTC] Sample at t + dT instead of the beginning of the control cycle (ros-controls#1306)
1 parent a5bb11b commit 1bd6870

File tree

6 files changed

+147
-73
lines changed

6 files changed

+147
-73
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -112,6 +112,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
112112
// Preallocate variables used in the realtime update() function
113113
trajectory_msgs::msg::JointTrajectoryPoint state_current_;
114114
trajectory_msgs::msg::JointTrajectoryPoint command_current_;
115+
trajectory_msgs::msg::JointTrajectoryPoint command_next_;
115116
trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
116117
trajectory_msgs::msg::JointTrajectoryPoint state_error_;
117118

@@ -124,6 +125,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
124125
// Parameters from ROS for joint_trajectory_controller
125126
std::shared_ptr<ParamListener> param_listener_;
126127
Params params_;
128+
rclcpp::Duration update_period_{0, 0};
127129

128130
trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
129131
/// Specify interpolation method. Default to splines.

joint_trajectory_controller/include/joint_trajectory_controller/trajectory.hpp

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -69,8 +69,10 @@ class Trajectory
6969
* acceleration respectively. Deduction assumes that the provided velocity or acceleration have to
7070
* be reached at the time defined in the segment.
7171
*
72-
* This function assumes that sampling is only done at monotonically increasing \p sample_time
73-
* for any trajectory.
72+
* This function by default assumes that sampling is only done at monotonically increasing \p
73+
* sample_time for any trajectory. That means, it will only search for a point matching the sample
74+
* time after the point it has been called before. If this isn't desired, set \p
75+
* search_monotonically_increasing to false.
7476
*
7577
* Specific case returns for start_segment_itr and end_segment_itr:
7678
* - Sampling before the trajectory start:
@@ -94,13 +96,16 @@ class Trajectory
9496
* description above.
9597
* \param[out] end_segment_itr Iterator to the end segment for given \p sample_time. See
9698
* description above.
99+
* \param[in] search_monotonically_increasing If set to true, the next sample call will start
100+
* searching in the trajectory at the index of this call's result.
97101
*/
98102
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
99103
bool sample(
100104
const rclcpp::Time & sample_time,
101105
const interpolation_methods::InterpolationMethod interpolation_method,
102106
trajectory_msgs::msg::JointTrajectoryPoint & output_state,
103-
TrajectoryPointConstIter & start_segment_itr, TrajectoryPointConstIter & end_segment_itr);
107+
TrajectoryPointConstIter & start_segment_itr, TrajectoryPointConstIter & end_segment_itr,
108+
const bool search_monotonically_increasing = true);
104109

105110
/**
106111
* Do interpolation between 2 states given a time in between their respective timestamps

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 21 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include <functional>
1919
#include <memory>
2020

21+
#include <stdexcept>
2122
#include <string>
2223
#include <vector>
2324

@@ -180,6 +181,7 @@ controller_interface::return_type JointTrajectoryController::update(
180181
if (has_active_trajectory())
181182
{
182183
bool first_sample = false;
184+
TrajectoryPointConstIter start_segment_itr, end_segment_itr;
183185
// if sampling the first time, set the point before you sample
184186
if (!traj_external_point_ptr_->is_sampled_already())
185187
{
@@ -196,11 +198,15 @@ controller_interface::return_type JointTrajectoryController::update(
196198
}
197199
}
198200

199-
// find segment for current timestamp
200-
TrajectoryPointConstIter start_segment_itr, end_segment_itr;
201-
const bool valid_point = traj_external_point_ptr_->sample(
201+
// Sample expected state from the trajectory
202+
traj_external_point_ptr_->sample(
202203
time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
203204

205+
// Sample setpoint for next control cycle
206+
const bool valid_point = traj_external_point_ptr_->sample(
207+
time + update_period_, interpolation_method_, command_next_, start_segment_itr,
208+
end_segment_itr, false);
209+
204210
if (valid_point)
205211
{
206212
const rclcpp::Time traj_start = traj_external_point_ptr_->time_from_start();
@@ -276,7 +282,7 @@ controller_interface::return_type JointTrajectoryController::update(
276282
// Update PIDs
277283
for (auto i = 0ul; i < dof_; ++i)
278284
{
279-
tmp_command_[i] = (state_desired_.velocities[i] * ff_velocity_scale_[i]) +
285+
tmp_command_[i] = (command_next_.velocities[i] * ff_velocity_scale_[i]) +
280286
pids_[i]->computeCommand(
281287
state_error_.positions[i], state_error_.velocities[i],
282288
(uint64_t)period.nanoseconds());
@@ -286,7 +292,7 @@ controller_interface::return_type JointTrajectoryController::update(
286292
// set values for next hardware write()
287293
if (has_position_command_interface_)
288294
{
289-
assign_interface_from_point(joint_command_interface_[0], state_desired_.positions);
295+
assign_interface_from_point(joint_command_interface_[0], command_next_.positions);
290296
}
291297
if (has_velocity_command_interface_)
292298
{
@@ -296,20 +302,20 @@ controller_interface::return_type JointTrajectoryController::update(
296302
}
297303
else
298304
{
299-
assign_interface_from_point(joint_command_interface_[1], state_desired_.velocities);
305+
assign_interface_from_point(joint_command_interface_[1], command_next_.velocities);
300306
}
301307
}
302308
if (has_acceleration_command_interface_)
303309
{
304-
assign_interface_from_point(joint_command_interface_[2], state_desired_.accelerations);
310+
assign_interface_from_point(joint_command_interface_[2], command_next_.accelerations);
305311
}
306312
if (has_effort_command_interface_)
307313
{
308314
assign_interface_from_point(joint_command_interface_[3], tmp_command_);
309315
}
310316

311317
// store the previous command. Used in open-loop control mode
312-
last_commanded_state_ = state_desired_;
318+
last_commanded_state_ = command_next_;
313319
}
314320

315321
if (active_goal)
@@ -867,6 +873,13 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
867873
std::string(get_node()->get_name()) + "/query_state",
868874
std::bind(&JointTrajectoryController::query_state_service, this, _1, _2));
869875

876+
if (get_update_rate() == 0)
877+
{
878+
throw std::runtime_error("Controller's update rate is set to 0. This should not happen!");
879+
}
880+
update_period_ =
881+
rclcpp::Duration(0.0, static_cast<uint32_t>(1.0e9 / static_cast<double>(get_update_rate())));
882+
870883
return CallbackReturn::SUCCESS;
871884
}
872885

joint_trajectory_controller/src/trajectory.cpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,8 @@ bool Trajectory::sample(
9191
const rclcpp::Time & sample_time,
9292
const interpolation_methods::InterpolationMethod interpolation_method,
9393
trajectory_msgs::msg::JointTrajectoryPoint & output_state,
94-
TrajectoryPointConstIter & start_segment_itr, TrajectoryPointConstIter & end_segment_itr)
94+
TrajectoryPointConstIter & start_segment_itr, TrajectoryPointConstIter & end_segment_itr,
95+
const bool search_monotonically_increasing)
9596
{
9697
THROW_ON_NULLPTR(trajectory_msg_)
9798

@@ -176,7 +177,10 @@ bool Trajectory::sample(
176177
}
177178
start_segment_itr = begin() + i;
178179
end_segment_itr = begin() + (i + 1);
179-
last_sample_idx_ = i;
180+
if (search_monotonically_increasing)
181+
{
182+
last_sample_idx_ = i;
183+
}
180184
return true;
181185
}
182186
}

0 commit comments

Comments
 (0)