You're reading the documentation for a development version. For the latest released version, please have a look at Jazzy.
Details about parameters
This controller uses the generate_parameter_library to handle its parameters. The parameter definition file located in the src folder contains descriptions for all the parameters used by the controller.
List of parameters
- joints (string_array)
Joint names of the system
Read only: True
Default: {}
Constraints:
contains no duplicates
length is greater than 0
- command_joints (string_array)
Joint names to control. If left empty,
joints
will be used. This parameters can be used if:JTC is used in a controller chain where command and state interfaces don’t have same names.
If the number of command joints is smaller than the degrees-of-freedom. For example to track the state and error of passive joints.
command_joints
must then be a subset ofjoints
.
Read only: True
Default: {}
Constraints:
contains no duplicates
- command_interfaces (string_array)
Command interfaces provided by the hardware interface for all joints
Read only: True
Default: {}
Constraints:
contains no duplicates
length is greater than 0
every element is one of the list [‘position’, ‘velocity’, ‘acceleration’, ‘effort’]
Custom validator: joint_trajectory_controller::command_interface_type_combinations
- state_interfaces (string_array)
State interfaces provided by the hardware for all joints.
Read only: True
Default: {}
Constraints:
contains no duplicates
length is greater than 0
every element is one of the list [‘position’, ‘velocity’, ‘acceleration’]
Custom validator: joint_trajectory_controller::state_interface_type_combinations
- allow_partial_joints_goal (bool)
Allow joint goals defining trajectory for only some joints.
Default: false
- open_loop_control (bool)
deprecated: use
interpolate_from_desired_state
and set feedback gains to zero insteadRead only: True
Default: false
- interpolate_from_desired_state (bool)
Interpolate from the current desired state when receiving a new trajectory.
The controller ignores the states provided by hardware interface but using last commands as states for starting the trajectory interpolation.
This is useful if hardware states are not following commands, i.e., an offset between those (typical for hydraulic manipulators). Furthermore, it is necessary if you have a reference trajectory that you send over multiple messages (e.g. for MPC-style trajectory planning).
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.Read only: True
Default: false
- allow_integration_in_goal_trajectories (bool)
Allow integration in goal trajectories to accept goals without position or velocity specified
Default: false
- set_last_command_interface_value_as_state_on_activation (bool)
When set to true, the last command interface value is used as both the current state and the last commanded state upon activation. When set to false, the current state is used for both.
Default: true
- action_monitor_rate (double)
Rate to monitor status changes when the controller is executing action (
control_msgs::action::FollowJointTrajectory
)Read only: True
Default: 20.0
Constraints:
greater than or equal to 0.1
- interpolation_method (string)
The type of interpolation to use, if any
Read only: True
Default: “splines”
Constraints:
one of the specified values: [‘splines’, ‘none’]
- allow_nonzero_velocity_at_trajectory_end (bool)
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 thanconstraints.goal_time
, otherwise ignored. If zero, timeout is deactivatedDefault: 0.0
- constraints
Default values for tolerances if no explicit values are set in the
JointTrajectory
message.- constraints.stopped_velocity_tolerance (double)
Velocity tolerance for at the end of the trajectory that indicates that controlled system is stopped.
Default: 0.01
- constraints.goal_time (double)
Time tolerance for achieving trajectory goal before or after commanded time. If set to zero, the controller will wait a potentially infinite amount of time.
Default: 0.0
Constraints:
greater than or equal to 0.0
- constraints.<joints>.trajectory (double)
Per-joint trajectory offset tolerance during movement.
Default: 0.0
- constraints.<joints>.goal (double)
Per-joint trajectory offset tolerance at the goal position.
Default: 0.0
- gains
If
velocity
is the only command interface for all joints or aneffort
command interface is configured, PID controllers are used for every joint. This structure contains the controller gains for every joint with the control law\[u = k_{ff} v_d + k_p e + k_i \sum e dt + k_d (v_d - v)\]with the desired velocity \(v_d\), the measured velocity \(v\), the position error \(e\) (definition see below), the controller period \(dt\), and the
velocity
oreffort
manipulated variable (control variable) \(u\), respectively.If the joint is of continuous type, the position error \(e = normalize(s_d - s)\) is normalized between \(-\pi, \pi\), i.e., the shortest rotation to the target position is the desired motion. Otherwise \(e = s_d - s\) is used, with the desired position \(s_d\) and the measured position \(s\) from the state interface.
If you want to turn off the PIDs (open loop control), set the feedback gains to zero.
- gains.<joints>.p (double)
Proportional gain \(k_p\) for PID
Default: 0.0
- gains.<joints>.i (double)
Integral gain \(k_i\) for PID
Default: 0.0
- gains.<joints>.d (double)
Derivative gain \(k_d\) for PID
Default: 0.0
- gains.<joints>.i_clamp (double)
Integral clamp. Symmetrical in both positive and negative direction.
Default: 0.0
- gains.<joints>.ff_velocity_scale (double)
Feed-forward scaling \(k_{ff}\) of velocity
Default: 0.0
An example parameter file
joint_trajectory_controller:
ros__parameters:
action_monitor_rate: 20.0
allow_integration_in_goal_trajectories: false
allow_nonzero_velocity_at_trajectory_end: false
allow_partial_joints_goal: false
cmd_timeout: 0.0
command_interfaces: '{}'
command_joints: '{}'
constraints:
<joints>:
goal: 0.0
trajectory: 0.0
goal_time: 0.0
stopped_velocity_tolerance: 0.01
gains:
<joints>:
d: 0.0
ff_velocity_scale: 0.0
i: 0.0
i_clamp: 0.0
p: 0.0
interpolate_from_desired_state: false
interpolation_method: splines
joints: '{}'
open_loop_control: false
set_last_command_interface_value_as_state_on_activation: true
state_interfaces: '{}'