Skip to content

Commit

Permalink
Update autodoc of parameters
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Dec 28, 2023
1 parent 0d7bd68 commit c6b06f5
Show file tree
Hide file tree
Showing 10 changed files with 151 additions and 202 deletions.
9 changes: 9 additions & 0 deletions diff_drive_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,11 @@ Parameters

This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.

List of parameters
=========================
.. generate_parameter_library_details:: ../src/diff_drive_controller_parameter.yaml


Note that the documentation on parameters for joint limits can be found in `their header file <https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/joint_limits/include/joint_limits/joint_limits_rosparam.hpp#L56-L75>`_.
Those parameters are:

Expand All @@ -80,3 +83,9 @@ angular.z [JointLimits structure]
Joint limits structure for the rotation about Z-axis.
The limiter ignores position limits.
For details see ``joint_limits`` package from ros2_control repository.

An example parameter file
=========================

.. generate_parameter_library_default::
../src/diff_drive_controller_parameter.yaml
10 changes: 10 additions & 0 deletions gripper_controllers/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -11,4 +11,14 @@ Parameters
^^^^^^^^^^^
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.

List of parameters
=========================

.. generate_parameter_library_details:: ../src/gripper_action_controller_parameters.yaml


An example parameter file
=========================

.. generate_parameter_library_default::
../src/gripper_action_controller_parameters.yaml
9 changes: 9 additions & 0 deletions imu_sensor_broadcaster/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -13,4 +13,13 @@ Parameters
^^^^^^^^^^^
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.

List of parameters
=========================
.. generate_parameter_library_details:: ../src/imu_sensor_broadcaster_parameters.yaml


An example parameter file
=========================

.. generate_parameter_library_default::
../src/imu_sensor_broadcaster_parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
map_interface_to_joint_state: |
Optional parameter (map) providing mapping between custom interface names to standard fields in ``joint_states`` message.
Usecases:
#. Hydraulics robots where feedback and commanded values often have an offset and reliance on open-loop control is common.
Typically one would map both values in separate interfaces in the framework.
To visualize those data multiple joint_state_broadcaster instances and robot_state_publishers would be used to visualize both values in RViz.
#. A robot provides multiple measuring techniques for its joint values which results in slightly different values.
Typically one would use separate interface for providing those values in the framework.
Using multiple joint_state_broadcaster instances we could publish and show both in RViz.
Format (each line is optional):
.. code-block:: yaml
\tmap_interface_to_joint_state:
\t\tposition: <custom_interface>
\t\tvelocity: <custom_interface>
\t\teffort: <custom_interface>
Examples:
.. code-block:: yaml
\tmap_interface_to_joint_state:
\t\tposition: kf_estimated_position
.. code-block:: yaml
\tmap_interface_to_joint_state:
\t\tvelocity: derived_velocity
\t\teffort: derived_effort
.. code-block:: yaml
\tmap_interface_to_joint_state:
\t\teffort: torque_sensor
.. code-block:: yaml
\tmap_interface_to_joint_state:
\t\teffort: current_sensor
58 changes: 9 additions & 49 deletions joint_state_broadcaster/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -24,56 +24,16 @@ Parameters
----------
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.

For an exemplary parameterization see the ``test`` folder of the controller's package.
List of parameters
=========================

map_interface_to_joint_state
Optional parameter (map) providing mapping between custom interface names to standard fields in ``joint_states`` message.
Usecases:
.. generate_parameter_library_details::
../src/joint_state_broadcaster_parameters.yaml
joint_state_broadcaster_parameter_context.yml

1. Hydraulics robots where feedback and commanded values often have an offset and reliance on open-loop control is common.
Typically one would map both values in separate interfaces in the framework.
To visualize those data multiple joint_state_broadcaster instances and robot_state_publishers would be used to visualize both values in RViz.

1. A robot provides multiple measuring techniques for its joint values which results in slightly different values.
Typically one would use separate interface for providing those values in the framework.
Using multiple joint_state_broadcaster instances we could publish and show both in RViz.
An example parameter file
=========================

Format (each line is optional):

.. code-block:: yaml
map_interface_to_joint_state:
position: <custom_interface>
velocity: <custom_interface>
effort: <custom_interface>
Examples:

.. code-block:: yaml
map_interface_to_joint_state:
position: kf_estimated_position
.. code-block:: yaml
map_interface_to_joint_state:
velocity: derived_velocity
effort: derived_effort
.. code-block:: yaml
map_interface_to_joint_state:
effort: torque_sensor
.. code-block:: yaml
map_interface_to_joint_state:
effort: current_sensor
Full list of parameters:

.. generate_parameter_library_details:: ../src/joint_state_broadcaster_parameters.yaml
.. generate_parameter_library_default::
../src/joint_state_broadcaster_parameters.yaml
149 changes: 10 additions & 139 deletions joint_trajectory_controller/doc/parameters.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,146 +5,17 @@
Details about parameters
^^^^^^^^^^^^^^^^^^^^^^^^

joints (list(string))
Joint names to control and listen to.
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.

command_joints (list(string))
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.
List of parameters
=========================

command_interface (list(string))
Command interfaces provided by the hardware interface for all joints.
.. generate_parameter_library_details::
../src/joint_trajectory_controller_parameters.yaml
parameters_context.yaml

Values: [position | velocity | acceleration] (multiple allowed)
An example parameter file
=========================

state_interfaces (list(string))
State interfaces provided by the hardware for all joints.

Values: position (mandatory) [velocity, [acceleration]].
Acceleration interface can only be used in combination with position and velocity.

action_monitor_rate (double)
Rate to monitor status changes when the controller is executing action (control_msgs::action::FollowJointTrajectory).

Default: 20.0

allow_partial_joints_goal (boolean)
Allow joint goals defining trajectory for only some joints.

Default: false

allow_integration_in_goal_trajectories (boolean)
Allow integration in goal trajectories to accept goals without position or velocity specified

Default: false

interpolation_method (string)
The type of interpolation to use, if any. Can be "splines" or "none".

Default: splines

open_loop_control (boolean)
Use controller in open-loop control mode:

* The controller ignores the states provided by hardware interface but using last commands as states for starting the trajectory interpolation.
* It deactivates the feedback control, see the ``gains`` structure.

This is useful if hardware states are not following commands, i.e., an offset between those (typical for hydraulic manipulators).

.. Note::
If this flag is set, the controller tries to read the values from the command interfaces on activation.
If they have real numeric values, those will be used instead of state interfaces.
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.

Default: false

start_with_holding (bool)
If true, start with holding position after activation. Otherwise, no command will be sent until
the first trajectory is received.

Default: true

allow_nonzero_velocity_at_trajectory_end (boolean)
If false, the last velocity point has to be zero or the goal will be rejected.

Default: false

cmd_timeout (double)
Timeout after which the input command is considered stale.
Timeout is counted from the end of the trajectory (the last point).
``cmd_timeout`` must be greater than ``constraints.goal_time``,
otherwise ignored.

If zero, timeout is deactivated"

Default: 0.0

constraints (structure)
Default values for tolerances if no explicit values are states in JointTrajectory message.

constraints.stopped_velocity_tolerance (double)
Default value for end velocity deviation.

Default: 0.01

constraints.goal_time (double)
Maximally allowed tolerance for not reaching the end of the trajectory in a predefined time.
If set to zero, the controller will wait a potentially infinite amount of time.

Default: 0.0 (not checked)

constraints.<joint_name>.trajectory (double)
Maximally allowed deviation from the target trajectory for a given joint.

Default: 0.0 (tolerance is not enforced)

constraints.<joint_name>.goal (double)
Maximally allowed deviation from the goal (end of the trajectory) for a given joint.

Default: 0.0 (tolerance is not enforced)

gains (structure)
Only relevant, if ``open_loop_control`` is not set.

If ``velocity`` is the only command interface for all joints or an ``effort`` command interface is configured, PID controllers are used for every joint.
This structure contains the controller gains for every joint with the control law

.. math::
u = k_{ff} v_d + k_p e + k_i \sum e dt + k_d (v_d - v)
with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see ``angle_wraparound`` below),
the controller period :math:`dt`, and the ``velocity`` or ``effort`` manipulated variable (control variable) :math:`u`, respectively.

gains.<joint_name>.p (double)
Proportional gain :math:`k_p` for PID

Default: 0.0

gains.<joint_name>.i (double)
Integral gain :math:`k_i` for PID

Default: 0.0

gains.<joint_name>.d (double)
Derivative gain :math:`k_d` for PID

Default: 0.0

gains.<joint_name>.i_clamp (double)
Integral clamp. Symmetrical in both positive and negative direction.

Default: 0.0

gains.<joint_name>.ff_velocity_scale (double)
Feed-forward scaling :math:`k_{ff}` of velocity

Default: 0.0

gains.<joint_name>.angle_wraparound (bool)
For joints that wrap around (without end stop, ie. are continuous),
where the shortest rotation to the target position is the desired motion.
If true, the position error :math:`e = normalize(s_d - s)` is normalized between :math:`-\pi, \pi`.
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
position :math:`s` from the state interface.

Default: false
.. generate_parameter_library_default::
../src/joint_trajectory_controller_parameters.yaml
13 changes: 13 additions & 0 deletions joint_trajectory_controller/doc/parameters_context.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
constraints:
Default values for tolerances if no explicit values are states in JointTrajectory message.

gains: |
Only relevant, if ``open_loop_control`` is not set.
If ``velocity`` is the only command interface for all joints or an ``effort`` command interface is configured, PID controllers are used for every joint.
This structure contains the controller gains for every joint with the control law
.. math:: u = k_{ff} v_d + k_p e + k_i \sum e dt + k_d (v_d - v)
with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see ``angle_wraparound`` below),
the controller period :math:`dt`, and the ``velocity`` or ``effort`` manipulated variable (control variable) :math:`u`, respectively.
Loading

0 comments on commit c6b06f5

Please sign in to comment.