Skip to content

Commit

Permalink
Fix traj message of set_hold_position
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Aug 24, 2023
1 parent 683d14c commit 291453c
Showing 1 changed file with 3 additions and 8 deletions.
11 changes: 3 additions & 8 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1469,21 +1469,16 @@ JointTrajectoryController::set_hold_position()
current_pose_msg.points[0].velocities.clear();
current_pose_msg.points[0].accelerations.clear();
current_pose_msg.points[0].effort.clear();
if (has_velocity_command_interface_)
if (has_velocity_command_interface_ || has_acceleration_command_interface_)
{
// ensure no velocity (PID will fix this)
// add velocity, so that trajectory sampling returns velocity points in any case
current_pose_msg.points[0].velocities.resize(dof_, 0.0);
}
if (has_acceleration_command_interface_)
{
// ensure no acceleration
// add velocity, so that trajectory sampling returns acceleration points in any case
current_pose_msg.points[0].accelerations.resize(dof_, 0.0);
}
if (has_effort_command_interface_)
{
// ensure no explicit effort (PID will fix this)
current_pose_msg.points[0].effort.resize(dof_, 0.0);
}

// set flag, otherwise tolerances will be checked with holding position too
rt_is_holding_.writeFromNonRT(true);
Expand Down

0 comments on commit 291453c

Please sign in to comment.