Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Joint trajectory controller detailed parameters don't exist on param server #149

Closed
livanov93 opened this issue Feb 10, 2021 · 4 comments
Closed

Comments

@livanov93
Copy link
Contributor

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

@destogl
Copy link
Member

destogl commented Feb 16, 2021

@livanov93 Can you explain a bit more about your test-setup and what is expected behavior and what is the issue?

@livanov93
Copy link
Contributor Author

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

@MGBla
Copy link

MGBla commented Feb 17, 2021

As it seems in ros2 contrary to ros1 parameters are only available if they were declared within a node

// with the lifecycle node being initialized, we can declare parameters
node_->declare_parameter<std::vector<std::string>>("joints", joint_names_);
node_->declare_parameter<double>("state_publish_rate", 50.0);
node_->declare_parameter<double>("action_monitor_rate", 20.0);
node_->declare_parameter<bool>("allow_partial_joints_goal", allow_partial_joints_goal_);
node_->declare_parameter<double>("constraints.stopped_velocity_tolerance", 0.01);
node_->declare_parameter<double>("constraints.goal_time", 0.0);

So the mechanic described here
* \brief Populate trajectory segment tolerances using data from the ROS node.
*
* It is assumed that the following parameter structure is followed on the provided LifecycleNode. Unspecified parameters
* will take the defaults shown in the comments:
*
* \code
* constraints:
* goal_time: 1.0 # Defaults to zero
* stopped_velocity_tolerance: 0.02 # Defaults to 0.01
* foo_joint:
* trajectory: 0.05 # Defaults to zero (ie. the tolerance is not enforced)
* goal: 0.03 # Defaults to zero (ie. the tolerance is not enforced)
* bar_joint:
* goal: 0.01
* \endcode
*
* \param node LifecycleNode where the tolerances are specified.
* \param joint_names Names of joints to look for in the parameter server for a tolerance specification.
* \return Trajectory segment tolerances.
does not really work.
I think two possible ways to deal with this are:

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.

@christophfroehlich
Copy link
Contributor

I think this issue is out of date since #384: the parameters should now be declared properly in ROS.

Concerning

I dare to close this issue now. Feel free to reopen if anything is not tackled with the other linked issues.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants