From 4b972eb7135a31e8184fbb598111f74a172077a7 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Thu, 28 Dec 2023 14:22:46 +0000 Subject: [PATCH] Update autodoc of parameters with nested parameters etc --- diff_drive_controller/doc/userdoc.rst | 9 ++ gripper_controllers/doc/userdoc.rst | 10 ++ imu_sensor_broadcaster/doc/userdoc.rst | 9 ++ ...nt_state_broadcaster_parameter_context.yml | 46 ++++++ joint_state_broadcaster/doc/userdoc.rst | 58 ++----- .../doc/parameters.rst | 149 ++---------------- .../doc/parameters_context.yaml | 13 ++ ...oint_trajectory_controller_parameters.yaml | 40 +++-- range_sensor_broadcaster/doc/userdoc.rst | 10 ++ 9 files changed, 142 insertions(+), 202 deletions(-) create mode 100644 joint_state_broadcaster/doc/joint_state_broadcaster_parameter_context.yml create mode 100644 joint_trajectory_controller/doc/parameters_context.yaml diff --git a/diff_drive_controller/doc/userdoc.rst b/diff_drive_controller/doc/userdoc.rst index c37d3bfd66..e405093983 100644 --- a/diff_drive_controller/doc/userdoc.rst +++ b/diff_drive_controller/doc/userdoc.rst @@ -66,8 +66,11 @@ Parameters This controller uses the `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 `_. Those parameters are: @@ -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 diff --git a/gripper_controllers/doc/userdoc.rst b/gripper_controllers/doc/userdoc.rst index 28262e90f9..01c7424566 100644 --- a/gripper_controllers/doc/userdoc.rst +++ b/gripper_controllers/doc/userdoc.rst @@ -11,4 +11,14 @@ Parameters ^^^^^^^^^^^ This controller uses the `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 diff --git a/imu_sensor_broadcaster/doc/userdoc.rst b/imu_sensor_broadcaster/doc/userdoc.rst index 3b8ae172db..f1f387aa67 100644 --- a/imu_sensor_broadcaster/doc/userdoc.rst +++ b/imu_sensor_broadcaster/doc/userdoc.rst @@ -13,4 +13,13 @@ Parameters ^^^^^^^^^^^ This controller uses the `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 diff --git a/joint_state_broadcaster/doc/joint_state_broadcaster_parameter_context.yml b/joint_state_broadcaster/doc/joint_state_broadcaster_parameter_context.yml new file mode 100644 index 0000000000..c96f8301ae --- /dev/null +++ b/joint_state_broadcaster/doc/joint_state_broadcaster_parameter_context.yml @@ -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: + \t\tvelocity: + \t\teffort: + + + 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 diff --git a/joint_state_broadcaster/doc/userdoc.rst b/joint_state_broadcaster/doc/userdoc.rst index 97fa75257e..884ae7d80d 100644 --- a/joint_state_broadcaster/doc/userdoc.rst +++ b/joint_state_broadcaster/doc/userdoc.rst @@ -24,56 +24,16 @@ Parameters ---------- This controller uses the `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: - velocity: - effort: - - - 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 diff --git a/joint_trajectory_controller/doc/parameters.rst b/joint_trajectory_controller/doc/parameters.rst index 8ad2b406d6..7bab14065b 100644 --- a/joint_trajectory_controller/doc/parameters.rst +++ b/joint_trajectory_controller/doc/parameters.rst @@ -5,146 +5,17 @@ Details about parameters ^^^^^^^^^^^^^^^^^^^^^^^^ -joints (list(string)) - Joint names to control and listen to. +This controller uses the `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::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..trajectory (double) - Maximally allowed deviation from the target trajectory for a given joint. - - Default: 0.0 (tolerance is not enforced) - -constraints..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..p (double) - Proportional gain :math:`k_p` for PID - - Default: 0.0 - -gains..i (double) - Integral gain :math:`k_i` for PID - - Default: 0.0 - -gains..d (double) - Derivative gain :math:`k_d` for PID - - Default: 0.0 - -gains..i_clamp (double) - Integral clamp. Symmetrical in both positive and negative direction. - - Default: 0.0 - -gains..ff_velocity_scale (double) - Feed-forward scaling :math:`k_{ff}` of velocity - - Default: 0.0 - -gains..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 diff --git a/joint_trajectory_controller/doc/parameters_context.yaml b/joint_trajectory_controller/doc/parameters_context.yaml new file mode 100644 index 0000000000..23f09a902b --- /dev/null +++ b/joint_trajectory_controller/doc/parameters_context.yaml @@ -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. diff --git a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml index 4981489d36..ded5bb7ca3 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml +++ b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml @@ -2,7 +2,7 @@ joint_trajectory_controller: joints: { type: string_array, default_value: [], - description: "Names of joints used by the controller", + description: "Joint names to control and listen to", read_only: true, validation: { unique<>: null, @@ -11,7 +11,7 @@ joint_trajectory_controller: command_joints: { type: string_array, default_value: [], - description: "Names of the commanding joints used by the controller", + description: "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.", read_only: true, validation: { unique<>: null, @@ -20,7 +20,7 @@ joint_trajectory_controller: command_interfaces: { type: string_array, default_value: [], - description: "Names of command interfaces to claim", + description: "Command interfaces provided by the hardware interface for all joints", read_only: true, validation: { unique<>: null, @@ -31,7 +31,7 @@ joint_trajectory_controller: state_interfaces: { type: string_array, default_value: [], - description: "Names of state interfaces to claim", + description: "State interfaces provided by the hardware for all joints.", read_only: true, validation: { unique<>: null, @@ -42,12 +42,21 @@ joint_trajectory_controller: allow_partial_joints_goal: { type: bool, default_value: false, - description: "Goals with partial set of joints are allowed", + description: "Allow joint goals defining trajectory for only some joints.", } open_loop_control: { type: bool, default_value: false, - description: "Run the controller in open-loop, i.e., read hardware states only when starting controller. This is useful when robot is not exactly following the commanded trajectory.", + description: "Use controller in open-loop control mode + \n\n + * The controller ignores the states provided by hardware interface but using last commands as states for starting the trajectory interpolation.\n + * It deactivates the feedback control, see the ``gains`` structure. + \n\n + This is useful if hardware states are not following commands, i.e., an offset between those (typical for hydraulic manipulators). + \n\n + 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::quiet_NaN()``) or state values when the hardware is started.\n", read_only: true, } allow_integration_in_goal_trajectories: { @@ -58,7 +67,7 @@ joint_trajectory_controller: action_monitor_rate: { type: double, default_value: 20.0, - description: "Rate status changes will be monitored", + description: "Rate to monitor status changes when the controller is executing action (control_msgs::action::FollowJointTrajectory)", read_only: true, validation: { gt_eq: [0.1] @@ -83,7 +92,7 @@ joint_trajectory_controller: default_value: 0.0, # seconds description: "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. + ``cmd_timeout`` must be greater than ``constraints.goal_time``, otherwise ignored. If zero, timeout is deactivated", } gains: @@ -91,17 +100,17 @@ joint_trajectory_controller: p: { type: double, default_value: 0.0, - description: "Proportional gain for PID" + description: "Proportional gain :math:`k_p` for PID" } i: { type: double, default_value: 0.0, - description: "Integral gain for PID" + description: "Integral gain :math:`k_i` for PID" } d: { type: double, default_value: 0.0, - description: "Derivative gain for PID" + description: "Derivative gain :math:`k_d` for PID" } i_clamp: { type: double, @@ -111,13 +120,16 @@ joint_trajectory_controller: ff_velocity_scale: { type: double, default_value: 0.0, - description: "Feed-forward scaling of velocity." + description: "Feed-forward scaling :math:`k_{ff}` of velocity" } angle_wraparound: { type: bool, default_value: false, - description: "For joints that wrap around (ie. are continuous). - Normalizes position-error to -pi to pi." + description: '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.' } constraints: stopped_velocity_tolerance: { diff --git a/range_sensor_broadcaster/doc/userdoc.rst b/range_sensor_broadcaster/doc/userdoc.rst index e35bec67ad..4c9bb4caee 100644 --- a/range_sensor_broadcaster/doc/userdoc.rst +++ b/range_sensor_broadcaster/doc/userdoc.rst @@ -11,5 +11,15 @@ The controller is a wrapper around ``RangeSensor`` semantic component (see ``con Parameters ^^^^^^^^^^^ +The Range Sensor Broadcaster uses the `generate_parameter_library `_ to handle its parameters. +List of parameters +========================= .. generate_parameter_library_details:: ../src/range_sensor_broadcaster_parameters.yaml + + +An example parameter file +========================= + +.. generate_parameter_library_default:: + ../src/range_sensor_broadcaster_parameters.yaml