@@ -128,14 +128,14 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
128
128
const auto active_goal = *rt_active_goal_.readFromRT ();
129
129
130
130
// Check if a new external message has been received from nonRT threads
131
- auto current_external_msg = traj_external_point_ptr_ ->get_trajectory_msg ();
132
- auto new_external_msg = traj_msg_external_point_ptr_ .readFromRT ();
131
+ auto current_external_msg = current_trajectory_ ->get_trajectory_msg ();
132
+ auto new_external_msg = new_trajectory_msg_ .readFromRT ();
133
133
// Discard, if a goal is pending but still not active (somewhere stuck in goal_handle_timer_)
134
134
if (current_external_msg != *new_external_msg && (*(rt_has_pending_goal_.readFromRT ()) && !active_goal) == false ) {
135
135
fill_partial_goal (*new_external_msg);
136
136
sort_to_local_joint_order (*new_external_msg);
137
137
// TODO(denis): Add here integration of position and velocity
138
- traj_external_point_ptr_ ->update (*new_external_msg);
138
+ current_trajectory_ ->update (*new_external_msg);
139
139
}
140
140
141
141
// TODO(anyone): can I here also use const on joint_interface since the reference_wrapper is not
@@ -166,22 +166,22 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
166
166
167
167
bool first_sample = false ;
168
168
// if sampling the first time, set the point before you sample
169
- if (!traj_external_point_ptr_ ->is_sampled_already ()) {
169
+ if (!current_trajectory_ ->is_sampled_already ()) {
170
170
first_sample = true ;
171
171
if (params_.open_loop_control ) {
172
- traj_external_point_ptr_ ->set_point_before_trajectory_msg (traj_time, last_commanded_state_);
172
+ current_trajectory_ ->set_point_before_trajectory_msg (traj_time, last_commanded_state_);
173
173
} else {
174
- traj_external_point_ptr_ ->set_point_before_trajectory_msg (traj_time, state_current_);
174
+ current_trajectory_ ->set_point_before_trajectory_msg (traj_time, state_current_);
175
175
}
176
176
}
177
177
178
178
// find segment for current timestamp
179
179
joint_trajectory_controller::TrajectoryPointConstIter start_segment_itr, end_segment_itr;
180
- const bool valid_point = traj_external_point_ptr_ ->sample (traj_time, interpolation_method_, state_desired_,
181
- start_segment_itr, end_segment_itr);
180
+ const bool valid_point = current_trajectory_ ->sample (traj_time, interpolation_method_, state_desired_,
181
+ start_segment_itr, end_segment_itr);
182
182
183
183
if (valid_point) {
184
- const rclcpp::Time traj_start = traj_external_point_ptr_ ->time_from_start ();
184
+ const rclcpp::Time traj_start = current_trajectory_ ->time_from_start ();
185
185
// this is the time instance
186
186
// - started with the first segment: when the first point will be reached (in the future)
187
187
// - later: when the point of the current segment was reached
@@ -193,16 +193,16 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
193
193
bool tolerance_violated_while_moving = false ;
194
194
bool outside_goal_tolerance = false ;
195
195
bool within_goal_time = true ;
196
- const bool before_last_point = end_segment_itr != traj_external_point_ptr_ ->end ();
196
+ const bool before_last_point = end_segment_itr != current_trajectory_ ->end ();
197
197
198
198
// have we reached the end, are not holding position, and is a timeout configured?
199
199
// Check independently of other tolerances
200
200
if (!before_last_point && *(rt_is_holding_.readFromRT ()) == false && cmd_timeout_ > 0.0 &&
201
201
time_difference > cmd_timeout_) {
202
202
RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to command timeout" );
203
203
204
- traj_msg_external_point_ptr_ .reset ();
205
- traj_msg_external_point_ptr_ .initRT (set_hold_position ());
204
+ new_trajectory_msg_ .reset ();
205
+ new_trajectory_msg_ .initRT (set_hold_position ());
206
206
}
207
207
208
208
// Check state/goal tolerance
@@ -291,8 +291,8 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
291
291
292
292
RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to state tolerance violation" );
293
293
294
- traj_msg_external_point_ptr_ .reset ();
295
- traj_msg_external_point_ptr_ .initRT (set_hold_position ());
294
+ new_trajectory_msg_ .reset ();
295
+ new_trajectory_msg_ .initRT (set_hold_position ());
296
296
} else if (!before_last_point) { // check goal tolerance
297
297
if (!outside_goal_tolerance) {
298
298
auto res = std::make_shared<FollowJTrajAction::Result>();
@@ -305,8 +305,8 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
305
305
306
306
RCLCPP_INFO (get_node ()->get_logger (), " Goal reached, success!" );
307
307
308
- traj_msg_external_point_ptr_ .reset ();
309
- traj_msg_external_point_ptr_ .initRT (set_hold_position ());
308
+ new_trajectory_msg_ .reset ();
309
+ new_trajectory_msg_ .initRT (set_hold_position ());
310
310
} else if (!within_goal_time) {
311
311
auto result = std::make_shared<FollowJTrajAction::Result>();
312
312
result->set__error_code (FollowJTrajAction::Result::GOAL_TOLERANCE_VIOLATED);
@@ -319,21 +319,21 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
319
319
RCLCPP_WARN (get_node ()->get_logger (), " Aborted due goal_time_tolerance exceeding by %f seconds" ,
320
320
time_difference);
321
321
322
- traj_msg_external_point_ptr_ .reset ();
323
- traj_msg_external_point_ptr_ .initRT (set_hold_position ());
322
+ new_trajectory_msg_ .reset ();
323
+ new_trajectory_msg_ .initRT (set_hold_position ());
324
324
}
325
325
}
326
326
} else if (tolerance_violated_while_moving && *(rt_has_pending_goal_.readFromRT ()) == false ) {
327
327
// we need to ensure that there is no pending goal -> we get a race condition otherwise
328
328
RCLCPP_ERROR (get_node ()->get_logger (), " Holding position due to state tolerance violation" );
329
329
330
- traj_msg_external_point_ptr_ .reset ();
331
- traj_msg_external_point_ptr_ .initRT (set_hold_position ());
330
+ new_trajectory_msg_ .reset ();
331
+ new_trajectory_msg_ .initRT (set_hold_position ());
332
332
} else if (!before_last_point && !within_goal_time && *(rt_has_pending_goal_.readFromRT ()) == false ) {
333
333
RCLCPP_ERROR (get_node ()->get_logger (), " Exceeded goal_time_tolerance: holding position..." );
334
334
335
- traj_msg_external_point_ptr_ .reset ();
336
- traj_msg_external_point_ptr_ .initRT (set_hold_position ());
335
+ new_trajectory_msg_ .reset ();
336
+ new_trajectory_msg_ .initRT (set_hold_position ());
337
337
}
338
338
// else, run another cycle while waiting for outside_goal_tolerance
339
339
// to be satisfied (will stay in this state until new message arrives)
0 commit comments