Skip to content

Commit

Permalink
Adapted to JTC interpolation method feature (UniversalRobots#439)
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch authored Jul 18, 2022
1 parent fe88fb0 commit d4f0fe9
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion ur_controllers/src/scaled_joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,10 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
// find segment for current timestamp
joint_trajectory_controller::TrajectoryPointConstIter start_segment_itr, end_segment_itr;
const bool valid_point =
(*traj_point_active_ptr_)->sample(traj_time, state_desired, start_segment_itr, end_segment_itr);
(*traj_point_active_ptr_)
->sample(traj_time,
joint_trajectory_controller::interpolation_methods::InterpolationMethod::VARIABLE_DEGREE_SPLINE,
state_desired, start_segment_itr, end_segment_itr);

if (valid_point) {
bool abort = false;
Expand Down

0 comments on commit d4f0fe9

Please sign in to comment.