Skip to content

Commit 35ff9db

Browse files
Add trajectory start time
1 parent 81828bf commit 35ff9db

File tree

2 files changed

+37
-10
lines changed

2 files changed

+37
-10
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 10 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -177,11 +177,11 @@ controller_interface::return_type JointTrajectoryController::update(
177177
auto new_external_msg = traj_msg_external_point_ptr_.readFromRT();
178178
// Discard,
179179
// if a goal is pending but still not active (somewhere stuck in goal_handle_timer_)
180-
// and if use_closed_loop_control_law_: wait until control law is computed by the traj_contr_
180+
// and if traj_contr_: wait until control law is computed by the traj_contr_
181181
if (
182182
current_external_msg != *new_external_msg &&
183183
(*(rt_has_pending_goal_.readFromRT()) && !active_goal) == false &&
184-
(use_closed_loop_control_law_ == false || traj_contr_->is_valid()))
184+
(traj_contr_ == nullptr || traj_contr_->is_ready()))
185185
{
186186
fill_partial_goal(*new_external_msg);
187187
sort_to_local_joint_order(*new_external_msg);
@@ -220,6 +220,11 @@ controller_interface::return_type JointTrajectoryController::update(
220220
{
221221
traj_external_point_ptr_->set_point_before_trajectory_msg(time, state_current_);
222222
}
223+
if (traj_contr_)
224+
{
225+
// set start time of trajectory to traj_contr_
226+
traj_contr_->start(time, traj_external_point_ptr_->time_from_start());
227+
}
223228
}
224229

225230
// find segment for current timestamp
@@ -292,7 +297,7 @@ controller_interface::return_type JointTrajectoryController::update(
292297
// set values for next hardware write() if tolerance is met
293298
if (!tolerance_violated_while_moving && within_goal_time)
294299
{
295-
if (use_closed_loop_control_law_)
300+
if (traj_contr_)
296301
{
297302
traj_contr_->computeCommands(
298303
tmp_command_, state_current_, state_error_, state_desired_, time, period);
@@ -1043,7 +1048,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
10431048
cmd_timeout_ = 0.0;
10441049
}
10451050

1046-
if (use_closed_loop_control_law_)
1051+
if (traj_contr_)
10471052
{
10481053
traj_contr_->activate();
10491054
}
@@ -1516,7 +1521,7 @@ void JointTrajectoryController::add_new_trajectory_msg(
15161521
traj_msg_external_point_ptr_.writeFromNonRT(traj_msg);
15171522

15181523
// compute gains of controller
1519-
if (use_closed_loop_control_law_)
1524+
if (traj_contr_)
15201525
{
15211526
if (traj_contr_->computeControlLawNonRT(traj_msg) == false)
15221527
{

joint_trajectory_controller_plugins/include/joint_trajectory_controller_plugins/trajectory_controller_base.hpp

Lines changed: 27 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -75,12 +75,30 @@ class TrajectoryControllerBase
7575
bool computeControlLawNonRT(
7676
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & trajectory)
7777
{
78-
rt_controller_valid_.writeFromNonRT(false);
78+
rt_control_law_ready_.writeFromNonRT(false);
7979
auto ret = computeControlLaw(trajectory);
80-
rt_controller_valid_.writeFromNonRT(true);
80+
rt_control_law_ready_.writeFromNonRT(true);
8181
return ret;
8282
}
8383

84+
/**
85+
* @brief set the time when the current trajectory started
86+
*
87+
* (same logic as trajectory class)
88+
*/
89+
void start(const rclcpp::Time time, const rclcpp::Time trajectory_start_time)
90+
{
91+
if (trajectory_start_time.seconds() == 0.0)
92+
{
93+
trajectory_start_time_ = time;
94+
}
95+
else
96+
{
97+
trajectory_start_time_ = trajectory_start_time;
98+
}
99+
start_trajectory_ = true;
100+
}
101+
84102
/**
85103
* @brief update the gains from a RT thread
86104
*
@@ -108,16 +126,20 @@ class TrajectoryControllerBase
108126
virtual void reset() = 0;
109127

110128
/**
111-
* @return true if the control law is valid (updated with the trajectory)
129+
* @return true if the control law is ready (updated with the trajectory)
112130
*/
113131
JOINT_TRAJECTORY_CONTROLLER_PLUGINS_PUBLIC
114-
bool is_valid() { return rt_controller_valid_.readFromRT(); }
132+
bool is_ready() { return rt_control_law_ready_.readFromRT(); }
115133

116134
protected:
117135
// the node handle for parameter handling
118136
rclcpp_lifecycle::LifecycleNode::SharedPtr node_;
119137
// Are we computing the control law or is it valid?
120-
realtime_tools::RealtimeBuffer<bool> rt_controller_valid_;
138+
realtime_tools::RealtimeBuffer<bool> rt_control_law_ready_;
139+
// time when the current trajectory started, can be used to interpolate time-varying gains
140+
rclcpp::Time trajectory_start_time_;
141+
// use this variable to activate new gains from the non-RT thread
142+
bool start_trajectory_ = false;
121143

122144
/**
123145
* @brief compute the control law from the given trajectory

0 commit comments

Comments
 (0)