ros2_controllers
ros2_controllers copied to clipboard
Joint trajectory controller detailed parameters don't exist on param server
As stated here and here parameters for checking the error through trajectory and on the goal position are not propagated on the parameter server. We also had problems with checking the errors on the last trajectory point - the problem occurs here
@livanov93 Can you explain a bit more about your test-setup and what is expected behavior and what is the issue?
While testing joint_trajectory_controller on the real hardware I was getting the Aborted due to goal tolerance violation
error. Afterwards, decided to add parameter per joint to increase goal tolerance:
The paramaters were defined in the following manner:
controller_manager:
ros__parameters:
update_rate: 600 # Hz
forward_command_controller_position:
type: forward_command_controller/ForwardCommandController
joint_state_controller:
type: joint_state_controller/JointStateController
ur_joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController
ur_joint_trajectory_controller:
ros__parameters:
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
state_publish_rate: 100.0
action_monitor_rate: 20.0
allow_partial_joints_goal: false
constraints:
stopped_velocity_tolerance: 0.01
goal_time: 0.0
shoulder_pan_joint:
trajectory: 0.05
goal: 0.03
shoulder_lift_joint:
trajectory: 0.05
goal: 0.03
elbow_joint:
trajectory: 0.05
goal: 0.03
wrist_1_joint:
trajectory: 0.05
goal: 0.03
wrist_2_joint:
trajectory: 0.05
goal: 0.03
wrist_3_joint:
trajectory: 0.05
goal: 0.03
forward_command_controller_position:
ros__parameters:
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
interface_name: position
This did not help at all but the worse thing is that parameter were not on the parameter server: There were only the following parameters:
/ur_joint_trajectory_controller:
action_monitor_rate
allow_partial_joints_goal
constraints.goal_time
constraints.stopped_velocity_tolerance
joints
state_publish_rate
use_sim_time
As it seems in ros2 contrary to ros1 parameters are only available if they were declared within a node https://github.com/ros-controls/ros2_controllers/blob/a80ce8d2b9a22fa83978976bc4257ede70dbc810/joint_trajectory_controller/src/joint_trajectory_controller.cpp#L65-L71 So the mechanic described here https://github.com/ros-controls/ros2_controllers/blob/a80ce8d2b9a22fa83978976bc4257ede70dbc810/joint_trajectory_controller/include/joint_trajectory_controller/tolerances.hpp#L78-L96 does not really work. I think two possible ways to deal with this are:
- Declare the constraints parameter for each element of the
joints
parameter or - Properly use the interface of the
FollowJointTrajectory
action (https://github.com/ros-controls/control_msgs/blob/foxy-devel/control_msgs/action/FollowJointTrajectory.action) where a JointTolerance is already defined (https://github.com/ros-controls/control_msgs/blob/foxy-devel/control_msgs/msg/JointTolerance.msg)
Personally I would prefer the second approach since this would enable us to dynamically adjust the tolerances for different trajectories without always adjusting the parameter server.