Skip to content

Commit

Permalink
Fix JointTrajectoryController for trajectories with a single point
Browse files Browse the repository at this point in the history
Signed-off-by: Andrej Orsula <[email protected]>
  • Loading branch information
AndrejOrsula committed Dec 20, 2021
1 parent 6b7a121 commit 254b01e
Showing 1 changed file with 0 additions and 2 deletions.
2 changes: 0 additions & 2 deletions kinova_driver/src/kinova_joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,8 +171,6 @@ void JointTrajectoryController::commandCB(const trajectory_msgs::JointTrajectory
kinova_angle_command_[i].Actuator7 = traj_command_points_[i].velocities[6] *180/M_PI;
}
}
// replace last velocity command (which is zero) to previous non-zero value, trying to drive robot moving a forward to get closer to the goal.
kinova_angle_command_[traj_command_points_.size()-1] = kinova_angle_command_[traj_command_points_.size()-2];

std::vector<double> durations(traj_command_points_.size(), 0.0); // computed by time_from_start
double trajectory_duration = traj_command_points_[0].time_from_start.toSec();
Expand Down

0 comments on commit 254b01e

Please sign in to comment.