ros_controllers
ros_controllers copied to clipboard
High jerks in acceleration profile on implementing joint_trajectory_controller: pos_vel_acc_controllers
I am using ros-kinetic version on Ubuntu 16.04 . I am sending trajectories from MoveIt to ros control to move my 7 DOF arm. To analyse trajectory, I compared trajectory given by MoveIt with the output of ros control and found that acceleration profile of ros control output has so many jerks and overshoots and is not following MoveIt trajectory.
I have subscribed from /position_trajectory_controller/command to get output from ros control. I have plotted the trajectory using octave in both cases.
I suspected that spline interpolation is not happening in ros control as my hardware interface is PositionJointInterface and controller I am using is
position_controllers/JointTrajectoryController (while spline interpolation happens only when position, velocity , acceleration values are sent as inputs) .
I then changed my hardware interface to PosVelAccJointInterface and controller to pos_vel_acc_controllers/JointTrajectoryController in relevant files(urdf,config and relevant cpp files) and found no changes in my acceleration profile.
PFA of acceleration profile in both cases

Can anyone please assist me on this??
Thanks and Regards, Prashanthi Tata
hello... any update on this??
Hi, I think your problem description is not enough for the investigation. Could you show your problem as everyone can reproduce? BTW I introduce my rqt_joint_trajectory_plot tool to plot the joint profile :smiley_cat:
Hi!! Here are the steps to be followed to reproduce my problem
- I ve used package https://github.com/IFL-CAMP/iiwa_stack and added few executables to send waypoints (executables attached below)
-
Waypoints(position, velocity, acceleration) are sent from MoveIt! to /iiwa/PositionJointInterface_trajectory_controller/command topic (using csv_to_controller_direct_main.cpp)
-
Interpolated points coming out of ros-controllers are collected from /iiwa/PositionJointInterface_trajectory_controller/state (using controller_to_csv_main.cpp)
-
Acceleration profiles of both MoveIt! and ros-controller are compared using octave tool and high jerks are observed in ros-controller's acceleration profile
Looks like your hardware cannot follow your command.
You might want to check your limits.
I'd guess that the error offset is quite high (in state topic).
I noticed that the joint_limit_interface (used in your HW), does not work properly in open-loop setups..
I then changed my hardware interface to PosVelAccJointInterface [...] and found no changes in my acceleration profile.
It should not change; the generated trajectory is the same for all interfaces.
@ipa-mdl: could the joint_trajectory_controller be a weak point here?
I'm currently working with hw that absolutely requires jerk-limited trajectories and afaict the JTC is not able to guarantee that (quintic splines). It's all position controlled though, so iiuc open-loop with ros_control and the default controllers.
could the joint_trajectory_controller be a weak point here?
Yes, it it not yet suitable for all control problems.. However, it might work better with sane input trajectories (something adapted to the HW capabilites). MoveIt! trajectories are not that optimized for actual control.
could the joint_trajectory_controller be a weak point here?
Yes, it it not yet suitable for all control problems..
It is almost the go-to solution though if you'd want a relative straightforward-to-setup configuration with a FollowJointTrajectory interface and ros_control.
What would you recommend the OP uses / does?
It is almost the go-to solution though if you'd want a relative straightforward-to-setup configuration with a FollowJointTrajectory interface and ros_control.
I ve tried to communicate using FollowJointTrajectory action too. Result is same with jerks and overshoots
I'm currently working with hw that absolutely requires jerk-limited trajectories and afaict the JTC is not able to guarantee that (quintic splines).
Do you have a suggestion for a better interpolation? It shouldn't be hard to extend this part with other configurable interpolations.
However, it might work better with sane input trajectories (something adapted to the HW capabilites).
MoveIt! trajectories are not that optimized for actual control.
@ipa-mdl Yes... when i generated my own custom trajectory and sent, acceleration profiles of ros-control was following MoveIt! acceleration profile. But the problem is, in general,trajectory points to my 7 DOF arm are sent from moveit . So the high jerks are observed
But the problem is, in general,trajectory points to my 7 DOF arm are sent from moveit . So the high jerks are observed
Have you tried smoothing on the moveit side in a post-processing step? http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/planning_adapters/planning_adapters_tutorial.html#running-ompl-as-a-pre-processor-for-stomp
Not the solution, but one work around can be use of Impedance Control
Acceleration = K_p(currentAngle - desiredAngle) + K_v (currentVelocity - desiredVelocity) + desiredAcceleration torque = M * Acceleration + Coriolis*Velcoity + Gravity + friction
You can use these computed torques and simulate your angle, velocity and acceleration waypoints using EffortController !