Skip to content

Commit e2b22b1

Browse files
Handle api changes related to traj_external_point_ptr_ (#779)
* Handle api changes related to traj_external_point_ptr_ Signed-off-by: Yadunund <[email protected]> * Fix formatting --------- Signed-off-by: Yadunund <[email protected]> Co-authored-by: Robert Wilbrandt <[email protected]>
1 parent 62f0a58 commit e2b22b1

File tree

1 file changed

+8
-10
lines changed

1 file changed

+8
-10
lines changed

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 8 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -157,7 +157,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
157157
}
158158

159159
// currently carrying out a trajectory
160-
if (traj_point_active_ptr_ && (*traj_point_active_ptr_)->has_trajectory_msg()) {
160+
if (has_active_trajectory()) {
161161
// Main Speed scaling difference...
162162
// Adjust time with scaling factor
163163
TimeData time_data;
@@ -169,23 +169,21 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
169169
time_data_.writeFromNonRT(time_data);
170170

171171
// if sampling the first time, set the point before you sample
172-
if (!(*traj_point_active_ptr_)->is_sampled_already()) {
173-
(*traj_point_active_ptr_)->set_point_before_trajectory_msg(traj_time, state_current);
172+
if (!traj_external_point_ptr_->is_sampled_already()) {
173+
traj_external_point_ptr_->set_point_before_trajectory_msg(traj_time, state_current);
174174
}
175175
resize_joint_trajectory_point(state_error, joint_num);
176176

177177
// find segment for current timestamp
178178
joint_trajectory_controller::TrajectoryPointConstIter start_segment_itr, end_segment_itr;
179-
const bool valid_point =
180-
(*traj_point_active_ptr_)
181-
->sample(traj_time,
182-
joint_trajectory_controller::interpolation_methods::InterpolationMethod::VARIABLE_DEGREE_SPLINE,
183-
state_desired, start_segment_itr, end_segment_itr);
179+
const bool valid_point = traj_external_point_ptr_->sample(
180+
traj_time, joint_trajectory_controller::interpolation_methods::InterpolationMethod::VARIABLE_DEGREE_SPLINE,
181+
state_desired, start_segment_itr, end_segment_itr);
184182

185183
if (valid_point) {
186184
bool abort = false;
187185
bool outside_goal_tolerance = false;
188-
const bool before_last_point = end_segment_itr != (*traj_point_active_ptr_)->end();
186+
const bool before_last_point = end_segment_itr != traj_external_point_ptr_->end();
189187

190188
// set values for next hardware write()
191189
if (has_position_command_interface_) {
@@ -251,7 +249,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
251249
RCLCPP_INFO(get_node()->get_logger(), "Goal reached, success!");
252250
} else if (default_tolerances_.goal_time_tolerance != 0.0) {
253251
// if we exceed goal_time_toleralance set it to aborted
254-
const rclcpp::Time traj_start = (*traj_point_active_ptr_)->get_trajectory_start_time();
252+
const rclcpp::Time traj_start = traj_external_point_ptr_->get_trajectory_start_time();
255253
const rclcpp::Time traj_end = traj_start + start_segment_itr->time_from_start;
256254

257255
// TODO(anyone): This will break in speed scaling we have to discuss how to handle the goal

0 commit comments

Comments
 (0)