Robot Configuration¶
Configuration File¶
The robot drivers based on NJointBlmcRobotDriver
are
configured via YAML files, which has to be passed to the function that creates the
backend (for example, see Example: Single-finger Position Control).
Default configurations for the different (Tri-)Finger robots can be found in the
config/
folder of the robot_fingers package.
Options¶
Note
Some of the options below expect a list with one value for each joint. They are
annotated with the type list[N_joints]
. The actual length of the list depends on
the number of joints of the robot. The order of the joints is implicitly defined by
can_ports
.
For (Tri-)Finger robots, the order is expected to be as described in Joint Order and Direction.
- can_ports : list¶
List of the CAN interface names to which the robot is connected. Example:
["can0", "can1", "can2"]
.The joints will be ordered accordingly (e.g. in actions and observations), i.e. for the above example, the joint order will be
[can0-motorA, can0-motorB, can1-motorA, ...]
Note: For (Tri-)Finger robots, the order is expected to be as described in Joint Order and Direction. So make sure to connect/configure the CAN interfaces accordingly.
-
max_current_A : float =
0.0
¶ Maximum current [in Ampere] that can be sent to the motor. Commands that result in higher torques will be clipped to the maximum.
See Safety Checks.
-
has_endstop : bool =
false
¶ Specify whether the joints have physical end stops or not.
This is, for example, relevant for homing, where the end stop can be used to determine the absolute joint positions. See also
homing_method
.Note that not having end stops does not mean that the joint can rotate freely in general.
-
homing_method : str =
"NONE"
¶ Which method to use for homing. See Homing of the Joints for possible values.
- calibration¶
Map with parameters related to homing and initialisation.
-
endstop_search_torques_Nm : list[N_Joints] =
[0, ...]
¶ Torque that is used to find the end stop.
-
move_steps : int =
0
¶ Number of time steps for reaching the initial position (see
initial_position_rad
) after homing.
-
endstop_search_torques_Nm : list[N_Joints] =
-
move_to_position_tolerance_rad : float =
0.0
¶ Tolerance [in radian] for reaching the target with
robot_fingers::NJointBlmcRobotDriver::move_to_position()
(used during initialization and shutdown).
-
safety_kd : list[N_Joints] =
[0.1, ...]
¶ D-gain to dampen velocity. The default value is rather high to be on the safe side. Depending in the application you may want to reduce it, to allow faster motions.
Set to zero to completely disable damping.
See Safety Checks.
- position_control_gains¶
Map with default control gains for the position PD controller.
-
kp : list[N_joints] =
[0, ...]
¶ Default P-gain for the position controller.
-
kd : list[N_joints] =
[0, ...]
¶ Default D-gain for the position controller.
-
kp : list[N_joints] =
-
hard_position_limits_lower : list[N_joints] =
[0, ...]
¶ Hard lower limits for joint position. Exceeding the limit with any joint results in an error and robot shutdown.
-
hard_position_limits_upper : list[N_joints] =
[0, ...]
¶ Hard upper limits for joint position. Exceeding the limit with any joint results in an error and robot shutdown.
-
soft_position_limits_lower : list[N_joints] =
[-inf, ...]
¶ Soft lower limits for joint position.
Exceeding this limit with some joints results in the action for that joint being adjusted to move the joint back inside the limits.
See Safety Checks.
-
soft_position_limits_upper : list[N_joints] =
[inf, ...]
¶ Soft upper limits for joint position. See
soft_position_limits_lower
.
-
home_offset_rad : list[N_joints] =
[0, ...]
¶ Offset between home position and zero. See Homing of the Joints.
-
initial_position_rad : list[N_joints] =
[0, ...]
¶ Initial position to which the robot moves during initialization.
- shutdown_trajectory¶
Optional
Trajectory which is executed in the shutdown method. Use this to move the robot to a “rest position” during shutdown of the robot driver. It can consist of arbitrarily many steps. Leave it empty to not move during shutdown.
The trajectory is specified as a list of steps, each step consisting of the following values:
- target_position_rad : list[N_joints]¶
Target positions for the joints in radian.
- move_steps : int¶
Number of time steps for reaching the target position.
Example:
# first move slowly back to initial position - target_position_rad: [0, 0.9, -1.7, 0, 0.9, -1.7, 0, 0.9, -1.7] move_steps: 3000 # then move faster to the actual rest position. - target_position_rad: [1.57, 1.8, -2.5, 1.57, 1.8, -2.5, 1.57, 1.8, -2.5] move_steps: 1000
- run_duration_logfiles : list¶
Optional
List of file to which run duration logs are written.
You can specify multiple files here if you want to log the runtime of different independent components separately. For example on a robot with multiple manipulators, you can have a separate log for each manipulator, so if one of them is replaced, only the log file of this manipulator needs to be changed.
Example¶
As a complete example, this is the configuration file used for the TriFingerPro robots:
can_ports: ["can0", "can1", "can2", "can3", "can4", "can5"]
max_current_A: 2.2
has_endstop: true
homing_method: endstop_release
home_offset_rad: [-2.136, -2.442, +2.710, -2.136, -2.442, +2.710, -2.136, -2.442, +2.710]
move_to_position_tolerance_rad: 0.1
calibration:
endstop_search_torques_Nm:
- +0.3
- +0.3
- -0.2
- +0.3
- +0.3
- -0.2
- +0.3
- +0.3
- -0.2
move_steps: 500
safety_kd:
- 0.09
- 0.09
- 0.05
- 0.09
- 0.09
- 0.05
- 0.09
- 0.09
- 0.05
position_control_gains:
kp: [9, 9, 9, 9, 9, 9, 9, 9, 9]
kd: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01]
#hard_position_limits_lower: [-.inf, -.inf, -.inf, -.inf, -.inf, -.inf, -.inf, -.inf, -.inf]
#hard_position_limits_upper: [.inf, .inf, .inf, .inf, .inf, .inf, .inf, .inf, .inf]
hard_position_limits_lower:
- -1.0
- -1.67
- -2.8
- -1.0
- -1.67
- -2.8
- -1.0
- -1.67
- -2.8
hard_position_limits_upper:
- 1.5
- 1.67
- 2.8
- 1.5
- 1.67
- 2.8
- 1.5
- 1.67
- 2.8
# Set limits such that the motors cannot collide with the middle links
soft_position_limits_lower:
- -0.33
- 0.0
- -2.7
- -0.33
- 0.0
- -2.7
- -0.33
- 0.0
- -2.7
soft_position_limits_upper:
- 1.0
- 1.57
- 0.0
- 1.0
- 1.57
- 0.0
- 1.0
- 1.57
- 0.0
# Set the initial position such that it is still save when the stage is at the
# highest level.
initial_position_rad:
- 0
- 0.9
- -1.7
- 0
- 0.9
- -1.7
- 0
- 0.9
- -1.7
shutdown_trajectory:
# first move slowly back to initial position
- target_position_rad: [0, 0.9, -1.7, 0, 0.9, -1.7, 0, 0.9, -1.7]
move_steps: 3000
# then move to rest position (a position from which it cannot get stuck
# during homing for the next run and that is a good initial position for
# calibration on first run after power on).
- target_position_rad: [1.57, 1.8, -2.5, 1.57, 1.8, -2.5, 1.57, 1.8, -2.5]
move_steps: 1000