From f6b0ec4cd543e3909b5287da9c5703508078c59d Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Thu, 9 Mar 2023 12:45:43 +0000 Subject: [PATCH] [JTC] Add pid gain structure to documentation (#485) (#543) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Add pid gain structure to documentation * Remove trailing whitespace * Remove trailing colons (cherry picked from commit e0a373ab09cdf8c268bc3c8d14c4a3c0db59b724) Co-authored-by: Christoph Fröhlich --- joint_trajectory_controller/doc/userdoc.rst | 55 +++++++++++++++++---- 1 file changed, 45 insertions(+), 10 deletions(-) diff --git a/joint_trajectory_controller/doc/userdoc.rst b/joint_trajectory_controller/doc/userdoc.rst index 8230d7febb..5cfbb40852 100644 --- a/joint_trajectory_controller/doc/userdoc.rst +++ b/joint_trajectory_controller/doc/userdoc.rst @@ -105,37 +105,37 @@ A yaml file for using it could be: Details about parameters ^^^^^^^^^^^^^^^^^^^^^^^^ -joints (list(string)): +joints (list(string)) Joint names to control and listen to. -command_joints (list(string)): +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. -command_interface (list(string)): +command_interface (list(string)) Command interfaces provided by the hardware interface for all joints. Values: [position | velocity | acceleration] (multiple allowed) -state_interfaces (list(string)): +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. -state_publish_rate (double): +state_publish_rate (double) Publish-rate of the controller's "state" topic. Default: 50.0 -action_monitor_rate (double): +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_partial_joints_goal (boolean) Allow joint goals defining trajectory for only some joints. -open_loop_control (boolean): +open_loop_control (boolean) Use controller in open-loop control mode using ignoring the states provided by hardware interface and using last commands as states in the next control step. This is useful if hardware states are not following commands, i.e., an offset between those (typical for hydraulic manipulators). If this flag is set, the controller tries to read the values from the command interfaces on starting. If they have real numeric values, those will be used instead of state interfaces. Therefore it is important set command interfaces to NaN (std::numeric_limits::quiet_NaN()) or state values when the hardware is started. @@ -153,16 +153,51 @@ constraints.goal_time (double) Default: 0.0 (not checked) -constraints..trajectory +constraints..trajectory (double) Maximally allowed deviation from the target trajectory for a given joint. Default: 0.0 (tolerance is not enforced) -constraints..goal +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) + 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 (s_d - s) + k_i \sum(s_d - s) dt + k_d (v_d - v) + + with the desired velocity :math:`v_d` and position :math:`s_d`, + the measured velocity :math:`v` and position :math:`s`, the controller period :math:`dt`, + and the ``velocity`` or ``effort`` setpoint :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 ROS2 interface of the controller ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^