config/*SYROPOD_NAME*.yaml
Value used in setting ros loop frequency which denotes time period between cycles.
(type: double)
(default: 0.02)
(unit: seconds)
Sets whether manual posing system is on/off. Manual posing allows for the manual posing of the body independent of
the walking cycle and additive to any other posing.
(type: bool)
(default: true)
Sets whether auto posing system is on/off. Auto posing adjusts pose of body according to custom posing cycle
defined in config/auto_pose.yaml parameters. (see Auto Pose Parameter File below)
(type: bool)
(default: false)
Sets whether rough terrain mode is on/off. Rough terrain mode uses various tip sensing data and/or external planners to actively adjust tip
trajectory whilst approaching touchdown and estimates a walk plane for legs on uneven ground. Allows for traversal
of rough terrain, stair climbing and transitioning to/from inclined/declined terrain.
(type: bool)
(default: false)
Determines if admittance control is currently turned on/off.
(type: bool)
(default: false)
Determines if inclination posing compensation system is on/off. This system adds x/y linear posing to the robot
body to align the assumed centre of mass of the body directly above the support polygon of the legs whilst on
inclined terrain, as detected by onboard IMU. (Requires IMU correctly set up.)
(type: bool)
(default: false)
Determines if imu posing compensation system is on/off. This system adds pitch/roll posing to the robot body to
align it perpendicularly to gravity as detected via on-board IMU. (Requires PID tuning and IMU correctly set up.)
(type: bool)
(default: false)
Determines if desired joint position commands are output on a 'per joint' basis.
(i.e. Each joint has it's own joint position command topic.)
(type: bool)
(default: true)
Determines if desired joint state commands are output combined on a single topic. (eg: "/desired_joint_states)
(type: bool)
(default: true)
String ID of the Syropod type associated with this set of config parameters.
(type: string)
(example: "max")
Array of strings which are used to name and identify each leg in the robot model. Legs should be identified
clockwise from the front-right most leg.
(type: [string, string, string, ... string])
(example: [AR, BR, CR, CL, BL, AL])
Array of strings which are used to name and identify each 'potential' joint in a leg in the robot model. Joints
should be identified from the robot body to the leg tip.
(type: [string, string, string, ... string])
(example: [coxa, femur, tibia])
Array of strings which are used to name and identify each 'potential' link in a leg in the robot model. Links
should be identified from a MANDATORY link named 'base' at the robot body and down to the leg tip.
(type: [string, string, string, ... string])
(example: [base, coxa, femur, tibia])
Map of leg_id (see /syropod/parameters/leg_id) and corresponding degrees of freedom (number of joints) in that leg.
(type: {string: double, string: double, string: double, ... string: double})
(example: {AR: 3, BR: 3, CR: 3, CL: 5, BL: 3, AL: 3})
Map of parameters for each joint corresponding to various joint characteristics:
offset: The difference between the zero point for the joint in the robot model and the zero point for the motor
actuating that joint in hardware.
min: The minimum limit of the joint position in the robot model.
max: The maximum limit of the joint position in the robot model.
packed: The joint position in the robot model which defines the joint as being in a 'packed' state.
unpacked: The joint position in the robot model which defines the joint as being in a 'unpacked' state.
max_vel: The maximum allowable joint velocity in the robot model.
(type: {string: double, string: double, string: double, string: double, string: double, string: double})
(example: AR_coxa_joint_parameters: {offset: 0.0, min: -0.785, max: 0.785, packed: -1.57, unpacked 0.0, max_vel: 5.0})
(unit: radians)
Map of parameters for each link corresponding to classical Denavit–Hartenberg parameters for describing the
transformation of joints connected by the link:
d: The DH parameter representing offset along previous z-axis to the common normal. (unit: metres)
theta: The DH parameter representing angle about previous z axis, from old x-axis to new x-axis. (unit: radians)
r: The DH parameter representing length of the common normal. (unit: metres)
alpha: The DH parameter representing angle about common normal, form old z-axis to new z-axis. (unit: radians)
(type: {string: double, string: double, string: double, string: double})
(example: AR_femur_link_parameters: {d: 0.0, theta: 0.0, r: 0.07000, alpha: 0.0})
Bool denoting if inverse kinematics function will clamp joint positions to those limits defined in parameters.
(default: true)
(type: Bool)
Bool denoting if inverse kinematics function will clamp joint velocities to those limits defined in parameters.
(default: true)
(type: Bool)
Bool denoting if inverse kinematics function will ignore warnings of deviation from desired position due to exceeding joint position/velocity limits. Ignoring warnings stops warning messages from being sent to rosconsole.
(default: true)
(type: Bool)
String ID of the default gait to be used by the Syropod.
(type: string)
(default: tripod_gait)
Number of full steps cycles taken per second assuming a gait with swing ratio of 1.0 (i.e. No stance period).
For other gaits the effective step frequency is adjusted according to swing ratio defined
by the gait parameters. Swing ratio is defined as: swing_length / (swing_length + stance_length)
Eg: Tripod gait has swing ratio of 0.5 thus effective step frequency is half of parameter value.
Wave gait has swing ratio of 0.1666 thus effective step frequency is 1/6th of parameter value.
Note: This is an dynamically adjustable parameter and thus consists of a map of values which describe the
possible values of this parameter:
default: The default parameter value.
min: The minimum allowed parameter value.
max: The maximum allowed parameter value.
step: The increment/decrement step of this value when adjusted.
(type: {string: double, string: double, string: double, string: double})
(default: {default: 1.0, min: 0.001, max: 2.0, step: 0.1})
(unit: steps/s (Hz))
Defines the desired clearance of the leg tip above the default position during swing period of step cycle.
Note: This is an dynamically adjustable parameter and thus consists of a map of values which describe the
possible values of this parameter:
default: The default parameter value.
min: The minimum allowed parameter value.
max: The maximum allowed parameter value.
step: The increment/decrement step of this value when adjusted.
(type: {string: double, string: double, string: double, string: double})
(default: {default: 0.1, min: 0.01, max: 0.05, step: 0.005})
(unit: metres)
Defines the desired clearance of the body above the default tip positions, limited to maximum possible height
determined by morphology.
Note: This is an dynamically adjustable parameter and thus consists of a map of values which describe the
possible values of this parameter:
default: The default parameter value.
min: The minimum allowed parameter value.
max: The maximum allowed parameter value.
step: The increment/decrement step of this value when adjusted.
(type: {string: double, string: double, string: double, string: double})
(default: {default: 0.3, min: 0.1, max: 0.5, step: 0.05})
(unit: metres)
Defines the percentage of the lateral workspace to use to modify the default walking stance.
A value of -1.0/1.0 will move the default stance laterally to the minimum/maximum stance span as limited by the workspace.
Note: This is an dynamically adjustable parameter and thus consists of a map of values which describe the
possible values of this parameter:
default: The default parameter value.
min: The minimum allowed parameter value.
max: The maximum allowed parameter value.
step: The increment/decrement step of this value when adjusted.
(type: {string: double, string: double, string: double, string: double})
(default: {default: 0.0, min: -1.0, max: 1.0, step: 0.100})
(unit: percentage)
String which defines the type of velocity input required:
throttle: The controller expects all velocity inputs to be between 0.0 and 1.0 which describe a real world
velocity input of zero to the maximum possible body velocities.
real: The controller expects all velocity inputs to be in real world SI units, limited to maximum possible
body velocities.
(type: string)
(default: throttle)
Double between 0.0 and 1.0 which scales the input desired body velocity and is primarily used for debugging
purposes as a factor of safety.
(type: double)
(default: 1.0)
Bool which denotes whether defined cruise velocity inputs (see below) are used in cruise control mode.
Alternatively, the velocity inputs at the time of cruise control activation will be kept constant.
(type: bool)
(default: true)
A map of linear velocities and the values to be used as constant linear body velocity input when
'force_cruise_velocity' is true and cruise control is active.
(type: {string: double, string: double})
(default: {x: 0.001, y: 0.0)
(units: metres/s)
An angular velocity value to be used as constant angular body velocity input when 'force_cruise_velocity' is true
and cruise control is active.
(type: double)
(default: 0.0)
(units: radians/s)
A time limit for cruise control after which all input velocity values default to zero.
Setting this value to zero causes an infinite time limit.
(type: double)
(default: 0.0)
(units: seconds)
Map of x/y coordinates (in robot frame) of the position of the tip in this leg's default stance.
x: x-axis coordinate (positive x-axis is robot forward)
y: y-axis coordinate (positive y-axis is robot left)
(type: {string: double, string: double})
(unit: metres)
Bool which denotes if the last link of the model attempts to align itself parallel to the direction of a gravity
vector calculated from IMU data. If IMU data is not provided the gravity direction is assumed along the negative z
direction (downward). Gravity aligned tips uses redundancy in the leg define a target orientation and thus is
automatically turned off for legs with 3 or less degrees of freedom (joints).
(type: bool)
(default: false)
A value used as a threshold to determine if a leg has 'touched down' onto the step surface. This threshold is compared against any data coming through the 'tip_states' topic and is not limited to any specific unit, eg: force in N, pressure in Pa, current in A or normalised.
(type: double)
(default: 0.9)
A value used as a threshold to determine if a leg has 'lifted off' of the step surface. This threshold is compared against any data coming through the 'tip_states' topic and is not limited to any specific unit, eg: force in N, pressure in Pa, current in A or normalised.
(type: double)
(default: 0.1)
String which defines the auto-posing cycle to be used (if auto posing feature is activated).
These auto-posing cycle names are defined in config/auto_pose.yaml. Setting this parameters to 'auto'
will append the current gait selection name and attempt to choose an associate auto-pose cycle
(i.e. tripod_gait_pose).
(type: string)
(default: auto)
Determines if robot attempts unpacking/packing & startup/shutdown procedures. If false the robot will move
legs DIRECTLY from initial positions to required positions for walking.
(type: bool)
(default: false)
Determines the length of time in which to complete a DIRECT startup sequence (i.e. start_up_sequence == false).
(type: bool)
(default: 12.0)
(unit: seconds)
A map of PID controller gains for the IMU posing system. (Requires PID tuning to develop gain values)
(type: {string: double, string: double, string: double})
(default: {p: 0.0, i: 0.0, d: 0.0})
Map defining the maximum linear translational posing of the body along the x,y,z axes.
(type: {string: double, string: double, string: double})
(example: {x: 0.1, y: 0.2, z: 0.3})
(unit: metres)
Map defining the maximum angular rotational posing of the body around the x,y,z axes (roll/pitch/yaw).
(type: {string: double, string: double, string: double})
(example: {roll: 0.2, pitch: 0.4, yaw: 0.6})
(unit: radians)
Sets the maximum translational posing VELOCITY of the body along the x,y,z axes.
(type: double)
(default: 0.05)
(unit: metres/s)
Sets the maximum rotational posing VELOCITY of the body around the x,y,z axes (roll/pitch/yaw).
(type: double)
(default: 0.01)
(unit: rad/s)
Sets the leg manipulation mode between controlling the tip position ('tip_control') vs each individual joint
position ('joint_control').
(type: string)
(default: tip_control)
Determines if dynamic stiffness mode is on where set virtual stiffness is scaled determined on whether an
individual leg is swinging or adjacent to a swinging leg.
(type: bool)
(default: true)
Determines if force input method for admittance control is estimated using joint efforts.
Set to false if robot has tip force sensing capabilities.
(type: bool)
(default: false)
Time step used in admittance controller ODE solver.
(type: double)
(default: 0.5)
Virtual mass variable used in admittance controller spring-mass-damper virtualisation.
Note: This is a dynamically adjustable parameter and thus consists of a map of values which describe the possible
values of this parameter:
default: The default parameter value.
min: The minimum allowed parameter value.
max: The maximum allowed parameter value.
step: The increment/decrement step of this value when adjusted.
(type: {string: double, string: double, string: double, string: double})
(default: {default: 10, min: 1, max: 100, step: 5})
(unit: unitless)
Virtual stiffness variable used in admittance controller spring-mass-damper virtualisation.
Note: This is a dynamically adjustable parameter and thus consists of a map of values which describe the possible
values of this parameter:
default: The default parameter value.
min: The minimum allowed parameter value.
max: The maximum allowed parameter value.
step: The increment/decrement step of this value when adjusted.
(type: {string: double, string: double, string: double, string: double})
(default: {default: 10, min: 1, max: 50, step: 5})
(unit: unitless)
Virtual damping ratio variable used in admittance controller spring-mass-damper virtualisation.
Note: This is a dynamically adjustable parameter and thus consists of a map of values which describe the
possible values of this parameter:
default: The default parameter value.
min: The minimum allowed parameter value.
max: The maximum allowed parameter value.
step: The increment/decrement step of this value when adjusted.
(type: {string: double, string: double, string: double, string: double})
(default: {default: 0.8, min: 0.1, max: 10.0, step: 0.05})
(unit: unitless)
Gain used to scale input tip force values used in admittance controller.
Note: This is a dynamically adjustable parameter and thus consists of a map of values which describe the
possible values of this parameter:
default: The default parameter value.
min: The minimum allowed parameter value.
max: The maximum allowed parameter value.
step: The increment/decrement step of this value when adjusted.
(type: {string: double, string: double, string: double, string: double})
(default: {default: 0.1, min: 0.001, max: 100.0, step: 1.0})
(unit: unitless)
Value used to scale the default virtual stiffness up when an individual leg is adjacent to a swinging leg and
therefore under increased load.
(type: double)
(default: 5.0)
Value used to scale the default virtual stiffness down when an individual leg is swinging.
(type: double)
(default: 0.1)
Sets rosconsole verbosity levels. Options include: 'debug', 'info', 'warning', 'error', 'fatal'.
(type: string)
(default: info)
Allows debug output from moveToJointPosition function in pose controller.
(type: bool)
(default: false)
Allows debug output from stepToPosition function in pose controller.
(type: bool)
(default: false)
Allows debug output from swing trajectory generation in walk controller.
(type: bool)
(default: false)
Allows debug output from stance trajectory generation in walk controller.
(type: bool)
(default: false)
Allows debug output from executeSequence function in pose controller. Also used to optimise joint 'unpacked'
parameter.
(type: bool)
(default: false)
Allows debug output from workspace calculations in walk controller.
(type: bool)
(default: false)
Allows debug output from inverse kinematics engine.
(type: bool)
(default: false)
Turns on output for use in simulation in RVIZ.
(type: bool)
(default: false)
config/gait.yaml
Ratio of step phase in the 'stance' state (on ground)
(type: int)
Ratio of step phase in the 'swing' state (in air)
(type: int)
Base ratio of step phase each leg is offset from each other.
(type: int)
Multiplier for phase_offset which determines phase offset for each leg.
(type: [int, int, int, ... int])
Offset multiplier values are assigned clockwise from the front-right most leg (as per leg_id parameter)
(eg: AR, BR, CR, CL, BL, AL)
Example:
tripod_gait has stance:swing:offset ratio of 2:2:2.
Assuming a total phase length of 1000:
500 iterations (50%) of the step are stance,
500 iterations (50%) of the step are swing
The base phase offset is 500 iterations (50%).
With a offset_multiplier of [0,1,0,1,0,1], legs:
AR, CR and BL legs have an effective offset of 0*500 = 0 iterations (0%)
BL, CL and AL legs have an effective offset of 1*500 = 500 iterations (50%)
Example:
wave_gait has stance:swing:offset ratio of 10:2:2.
Assuming a total phase length of 600:
500 iterations (83.33%) of the step are stance,
100 iterations (16.67%) of the step are swing
The base phase offset is 100 iterations (16.67%).
With a offset_multiplier of [2,3,4,1,0,5], legs:
AR has an offset of 2*100 = 200 iterations (33.33%)
BR has an offset of 3*100 = 300 iterations (50%)
CR has an offset of 4*100 = 400 iterations (66.67%)
CL has an offset of 1*100 = 100 iterations (16.67%)
BL has an offset of 0*100 = 0 iterations (0%)
AL has an offset of 5*100 = 500 iterations (83.33%)
Note that for this example the swing state starts at iteration 250
(swing_start = stance_phase/2 = 500/2 = 250) and therefore these offsets
give a swing order of:
AR, CL, BL, AL, CR, BR, AR ...
config/auto_pose.yaml
The frequency at which this auto pose cycle repeats. Set to -1.0 to sync with step cycle.
(type: double)
(default: -1.0)
The phase length of the base auto pose cycle.
(type: int)
An array of phases which signify the start for each of any number of auto_pose cycles. Auto pose cycles may overlap
and if so will superpose.
(type: [int, int, int ... int])
An array of phases which signify the end for each of any number of auto_pose cycles. Auto pose cycles may overlap
and if so will superpose.
(type: [int, int, int ... int])
A map of phases which signify the start for each to negate any auto posing applied to it by auto-pose cycles.
(type: {string: int, string: int, string: int, ... string: int})
A map of phases which signify the end for each leg to negate any auto posing applied to it by auto-pose cycles.
(type: {string: int, string: int, string: int, ... string: int})
A map of ratios which define what portion of the negation phase is used to transition to/from zero & total negation.
(type: {string: double, string: double, string: double, ... string: double})
An array of values which define the amplitude of rotational angular body posing about the x-axis (roll) for each
of any number of auto pose cycles.
(type: [double, double, double ... double])
An array of values which define the amplitude of rotational angular body posing about the y-axis (pitch) for each
of any number of auto pose cycles.
(type: [double, double, double ... double])
An array of values which define the amplitude of rotational angular body posing about the z-axis (yaw) for each
of any number of auto pose cycles.
(type: [double, double, double ... double])
An array of values which define the amplitude of translational linear body posing in the x-axis for each of any
number of auto pose cycles.
(type: [double, double, double ... double])
An array of values which define the amplitude of translational linear body posing in the y-axis for each of any
number of auto pose cycles.
(type: [double, double, double ... double])
An array of values which define the amplitude of translational linear body posing in the z-axis for each of any
number of auto pose cycles.
(type: [double, double, double ... double])
An array of values which define the amplitude of translational linear body posing in the direction of gravity estimated from an IMU.
(type: [double, double, double ... double])