Ros2_control unsmooth motion

Hi Everyone,

I have recently been working with the Fast Robot Interface (FRI, control of KUKA LBR) and implemented the harware_interface::SystemInterface for it, see GitHub - KCL-BMEIS/lbr_fri_ros2_stack.

The joint_trajectory_controller/JointTrajectoryController is used for control. When sending joint positions via an action client, the resulting motion is unsmooth.

MoveIt2, which interfaces the same controller, runs smooth up to 200Hz. The motion is unsmooth beyond 200Hz. It seems they are using ruckig to smoothen the trajectories.

With ros_control in ROS1, sending position goals via an action client worked perfectly well. What am I doing wrong? Is there anything I am missing?

Thank you very much for reading, and for your response, kind regard
Martin

(I should mention that the ros2_control_node is executed with real time priority on the RT_PREEMPT linux patch)

Can you explain here a bit more what are you doing? Are you sending the full trajectory through action client or individual points? What is the source of those points? How are they interpoalted? Is it possible that robot reaches the points and start to slow-down before the next point is received, and this then results in unsmooth motion?

I know that MoveIt2 experimented with Rucking and we in ros2_control also did. For a bit different purpose, but the smoothening didn’t work as expected. I suppose that the main difference is that MoveIt sends trajectories and not points. Then JointTrajectoryController (JTC) process these trajectories as needed. This is usually results in the best/smoothest movement.

When you are mentioning 200Hz, what do you mean by that? Is this frequency of the ros2_control update loop? If so, could it be that your hardware is using blocking calls in read and write methods and this slows down the trajectory execution?

1 Like

hi @destogl, thanks for the prompt response. Just to clarify, it is very possible that I use the ros2_control horribly wrong.

I am trying to send a sinusoidal motion to the first joint, all other joint positions are set to zero. Therefore, at each step, I send a trajectory control_msgs::action::FollowJointTrajectory with a single point, using an action client. I feel like the robot has not reached the target position, when the new command arrives. Should I use position_controllers/JointGroupPositionController instead?

200 Hz refers to the ros2_control control loop frequency

there are indeed blocking calls, which is why I removed the sleep statements in the control loop.

don’t do this.

The JTC will try to perform trajectory replacement, which will not work too well with very short trajectories.

yes, or the velocity variant.

PS: could you please post these kinds of questions on ROS Answers instead in the future?

2 Likes

hi @gavanderhoorn , apologies for posting it here. I wasn’t aware of this.

I’ll try to use a different controller. Thanks for your help. Please feel free to delete.

I rather propose to generate the full or at least longer trajectory and then sent it using client. @gavanderhoorn explained you why this causes issues otherwise.

It sounds like you are generating/interpolating your trajectory, so yes, JointGroupPositionController could be a better solution.

Yeah, this is a thing… If you are using this, then the update rate of ros2_control_node does not have any influence on execution. At which frequency is running your hardware? I would guess probably something around 200Hz. So when you chose higher frequency JTC is interpolation for it, but you are not communicating faster to the hardware.

1 Like

The Fast Robot Interface was built by KUKA such that the controller and the controlling computer run at the same rate. The computer waits from messages by the controller and responds to them.

Thank you very much for your help, and apologies again.

That’s fine, but to do a proper control, you should know the exact rate at which the controller is running. Otherwise, you will never get perfect trajectories.

Thanks for the hint, so I usually set the rate to 100/200/500/1000 Hz. These rates are exact.

Just to give feedback, using the position_controllers/JointGroupPositionController controller indeed helps. Sending commands at the control rate makes the unsmooth motion disappear @destogl. Thank you very much for your help. And amazing work on ros2_control btw

1 Like

FYI Ruckig isn’t being used for MoveIt smoothing unless you went out of your way to specify it.

1 Like

ah okay, sorry I didn’t know. I just heard your recent talk about admittance control Online Trajectory Generation and Admittance Contro | PickNik, good talk btw, where you recommended to use ruckig, and then assumed MoveIt2 would default to it, too moveit2/ruckig_traj_smoothing.h at main · ros-planning/moveit2 · GitHub. But this was obviously wrong then. Thanks for letting me know @AndyZe.

1 Like