ros-controls / ros2_controllers

Generic robotic controllers to accompany ros2_control
https://control.ros.org
Apache License 2.0
356 stars 320 forks source link

false Goal reached, success! with joint trajectory controller #1088

Closed FrGe2016 closed 2 months ago

FrGe2016 commented 6 months ago

I have a slow home made robot, On every moves, the succes, for the slower joint, is confirmed a few seconds before the joint target is reached ? At this moment, there is still a significant distance to travel, ( we are not talking of oscillation around the target due to a not well adjusted PID)

christophfroehlich commented 6 months ago

Please give us some information: your ROS distro, ros2_control version, your controller configuration yaml etc.

FrGe2016 commented 6 months ago

I have ros2 Humble.

I have a real home made robot, controlled by a micro controller, the micro controller has a pid loop command on position, one tcp server stream the actual position and velocity to the hardware interface while another receive the position command. Of all the joints, the lateral joint is the slowest, it is a prismatic joint ( rack and pinion). The JTC confirm success while this joint is not at his destination ( time remaining 1,5 to 2 seconds )

g_controllers.yaml

```yaml controller_manager: ros__parameters: update_rate: 50 # Hz arm_controller: type: joint_trajectory_controller/JointTrajectoryController joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster arm_controller: ros__parameters: command_interfaces: - position state_interfaces: - position - velocity allow_partial_joints_goal: true joints: - elbow - wrist - rotator - lateral - gripper - gripper_top ```

g.ros2_control_arm.xacro

```xml mock_components/GenericSystem ${mock_sensor_commands} gazebo_ros2_control/GazeboSystem ign_ros2_control/IgnitionSystem f_hardware_interface/FBotHardwareInterface 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 ``` Velocity and acceleration limits are defined in the URDF
christophfroehlich commented 6 months ago

It would be very helpful if you format your comments appropriately.

Have a look at the documentation. You don't specify any of the constraints parameters, which means that JTC succeeds if every joint velocity is below 0.01units (default setting). This could be the case with your "slow actuator".

However, consider sending a feasible trajectory to your system which can be reached on time at least in the nominal case.

gavanderhoorn commented 6 months ago

one tcp server stream the actual position and velocity to the hardware interface

as it's a common pattern I see with 'cheap servos' (which can't report the actual current state): is this really the current state, or the last commanded state?

FrGe2016 commented 6 months ago

I have good feedback's with absolute angle measurements for my revolute joints an an encoder for my slow prismatic joint.I missed that part of the documentation, my starting point configuration files generated by moveit setup assistant. I will try to fix my problem with the available parameters. ( but my slow joint is not that slow and there is a factor of 70 compared with the other joints.) Setting a global parameter could be an issue. In last resort, i will modify the joint trajectory controller but i will try to avoid it .

christophfroehlich commented 2 months ago

Seems to be solved.