|
| 1 | +:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/joint_trajectory_controller/doc/parameters.rst |
| 2 | + |
| 3 | +.. _parameters: |
| 4 | + |
| 5 | +Details about parameters |
| 6 | +^^^^^^^^^^^^^^^^^^^^^^^^ |
| 7 | + |
| 8 | +joints (list(string)) |
| 9 | + Joint names to control and listen to. |
| 10 | + |
| 11 | +command_joints (list(string)) |
| 12 | + Joint names to control. This parameters is used if JTC is used in a controller chain where command and state interfaces don't have same names. |
| 13 | + |
| 14 | +command_interface (list(string)) |
| 15 | + Command interfaces provided by the hardware interface for all joints. |
| 16 | + |
| 17 | + Values: [position | velocity | acceleration] (multiple allowed) |
| 18 | + |
| 19 | +state_interfaces (list(string)) |
| 20 | + State interfaces provided by the hardware for all joints. |
| 21 | + |
| 22 | + Values: position (mandatory) [velocity, [acceleration]]. |
| 23 | + Acceleration interface can only be used in combination with position and velocity. |
| 24 | + |
| 25 | +state_publish_rate (double) |
| 26 | + Publish-rate of the controller's "state" topic. |
| 27 | + |
| 28 | + Default: 50.0 |
| 29 | + |
| 30 | +action_monitor_rate (double) |
| 31 | + Rate to monitor status changes when the controller is executing action (control_msgs::action::FollowJointTrajectory). |
| 32 | + |
| 33 | + Default: 20.0 |
| 34 | + |
| 35 | +allow_partial_joints_goal (boolean) |
| 36 | + Allow joint goals defining trajectory for only some joints. |
| 37 | + |
| 38 | + Default: false |
| 39 | + |
| 40 | +allow_integration_in_goal_trajectories (boolean) |
| 41 | + Allow integration in goal trajectories to accept goals without position or velocity specified |
| 42 | + |
| 43 | + Default: false |
| 44 | + |
| 45 | +interpolation_method (string) |
| 46 | + The type of interpolation to use, if any. Can be "splines" or "none". |
| 47 | + |
| 48 | + Default: splines |
| 49 | + |
| 50 | +open_loop_control (boolean) |
| 51 | + Use controller in open-loop control mode: |
| 52 | + |
| 53 | + * The controller ignores the states provided by hardware interface but using last commands as states for starting the trajectory interpolation. |
| 54 | + * It deactivates the feedback control, see the ``gains`` structure. |
| 55 | + |
| 56 | + This is useful if hardware states are not following commands, i.e., an offset between those (typical for hydraulic manipulators). |
| 57 | + |
| 58 | + .. Note:: |
| 59 | + If this flag is set, the controller tries to read the values from the command interfaces on activation. |
| 60 | + If they have real numeric values, those will be used instead of state interfaces. |
| 61 | + Therefore it is important set command interfaces to NaN (i.e., ``std::numeric_limits<double>::quiet_NaN()``) or state values when the hardware is started. |
| 62 | + |
| 63 | + Default: false |
| 64 | + |
| 65 | +allow_nonzero_velocity_at_trajectory_end (boolean) |
| 66 | + If false, the last velocity point has to be zero or the goal will be rejected. |
| 67 | + |
| 68 | + Default: true |
| 69 | + |
| 70 | +constraints (structure) |
| 71 | + Default values for tolerances if no explicit values are states in JointTrajectory message. |
| 72 | + |
| 73 | +constraints.stopped_velocity_tolerance (double) |
| 74 | + Default value for end velocity deviation. |
| 75 | + |
| 76 | + Default: 0.01 |
| 77 | + |
| 78 | +constraints.goal_time (double) |
| 79 | + Maximally allowed tolerance for not reaching the end of the trajectory in a predefined time. |
| 80 | + |
| 81 | + Default: 0.0 (not checked) |
| 82 | + |
| 83 | +constraints.<joint_name>.trajectory (double) |
| 84 | + Maximally allowed deviation from the target trajectory for a given joint. |
| 85 | + |
| 86 | + Default: 0.0 (tolerance is not enforced) |
| 87 | + |
| 88 | +constraints.<joint_name>.goal (double) |
| 89 | + Maximally allowed deviation from the goal (end of the trajectory) for a given joint. |
| 90 | + |
| 91 | + Default: 0.0 (tolerance is not enforced) |
| 92 | + |
| 93 | +gains (structure) |
| 94 | + Only relevant, if ``open_loop_control`` is not set. |
| 95 | + |
| 96 | + If ``velocity`` is the only command interface for all joints or an ``effort`` command interface is configured, PID controllers are used for every joint. |
| 97 | + This structure contains the controller gains for every joint with the control law |
| 98 | + |
| 99 | + .. math:: |
| 100 | +
|
| 101 | + u = k_{ff} v_d + k_p e + k_i \sum e dt + k_d (v_d - v) |
| 102 | +
|
| 103 | + with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see below), |
| 104 | + the controller period :math:`dt`, and the ``velocity`` or ``effort`` manipulated variable (control variable) :math:`u`, respectively. |
| 105 | + |
| 106 | +gains.<joint_name>.p (double) |
| 107 | + Proportional gain :math:`k_p` for PID |
| 108 | + |
| 109 | + Default: 0.0 |
| 110 | + |
| 111 | +gains.<joint_name>.i (double) |
| 112 | + Integral gain :math:`k_i` for PID |
| 113 | + |
| 114 | + Default: 0.0 |
| 115 | + |
| 116 | +gains.<joint_name>.d (double) |
| 117 | + Derivative gain :math:`k_d` for PID |
| 118 | + |
| 119 | + Default: 0.0 |
| 120 | + |
| 121 | +gains.<joint_name>.i_clamp (double) |
| 122 | + Integral clamp. Symmetrical in both positive and negative direction. |
| 123 | + |
| 124 | + Default: 0.0 |
| 125 | + |
| 126 | +gains.<joint_name>.ff_velocity_scale (double) |
| 127 | + Feed-forward scaling :math:`k_{ff}` of velocity |
| 128 | + |
| 129 | + Default: 0.0 |
| 130 | + |
| 131 | +gains.<joint_name>.normalize_error (bool) |
| 132 | + If true, the position error :math:`e = normalize(s_d - s)` is normalized between :math:`-\pi, \pi`. |
| 133 | + Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured |
| 134 | + position :math:`s` from the state interface. Use this for revolute joints without end stop, |
| 135 | + where the shortest rotation to the target position is the desired motion. |
| 136 | + |
| 137 | + Default: false |
0 commit comments