Extras
Despite all current customization options, we still would like our users to be able to add-in their existing custom URDF to the robot platform URDF and pass in and overwrite parameters to all platform nodes. Extras have the following entries:
- urdf:
- package: name of the ROS 2 package that contains the extras URDF (optional).
- path: relative path within the package or absolute path to robot extras URDF
- ros_parameters: in YAML to pass in parameters to platform nodes. This is useful to change parameters such as the robot's velocity and acceleration.
extras:
urdf:
package: package_name
path: relative/path/to/urdf/in/package.urdf.xacro # or can contain /absolute/path/to/urdf.urdf.xacro
launch:
package: package_name
path: relative/path/to/launch/in/package.launch.py
ros_parameters: {} # node parameters, see below
Remember, absolute paths start with / and relative paths do not.
ROS Parameters
A common use case is to set and update the parameters to the platform_velocity_controller node. These can be used to modify the linear and angular velocity and acceleratation.
These can be passed in as follows:
The wheel_radius parameter only needs to be set if you have physically changed the wheels. It can be omitted if you only want to adjust velocity or acceleration limits.
- A200
- D1X0-D
- D1X0-O
- J100
- R100
- W200
A200 Husky Controller Defaults:
platform:
extras:
ros_parameters:
platform_velocity_controller:
wheel_radius: 0.1651
linear.x.max_velocity: 1.0
linear.x.min_velocity: -1.0
linear.x.max_acceleration: 1.0
linear.x.min_acceleration: -1.0
angular.z.max_velocity: 1.0
angular.z.min_velocity: -1.0
angular.z.max_acceleration: 1.0
angular.z.min_acceleration: -1.0
D1X0-D Dingo-D Controller Defaults:
platform:
extras:
ros_parameters:
platform_velocity_controller:
wheel_radius: 0.049
linear.x.max_velocity: 1.3
linear.x.min_velocity: -1.3
linear.x.max_acceleration: 1.0
linear.x.min_acceleration: -1.0
angular.z.max_velocity: 4.0
angular.z.min_velocity: -4.0
angular.z.max_acceleration: 2.0
angular.z.min_acceleration: -2.0
D1X0-O Dingo-O Controller Defaults:
platform:
extras:
ros_parameters:
platform_velocity_controller:
kinematics.wheels_radius: 0.05
linear.x.max_velocity: 1.3
linear.x.min_velocity: -1.3
linear.x.max_acceleration: 1.0
linear.x.min_acceleration: -1.0
linear.y.max_velocity: 1.3
linear.y.min_velocity: -1.3
linear.y.max_acceleration: 1.0
linear.y.min_acceleration: -1.0
angular.z.max_velocity: 4.0
angular.z.min_velocity: -4.0
angular.z.max_acceleration: 2.0
angular.z.min_acceleration: -2.0
J100 Jackal Controller Defaults:
platform:
extras:
ros_parameters:
platform_velocity_controller:
wheel_radius: 0.098
linear.x.max_velocity: 2.0
linear.x.min_velocity: -2.0
linear.x.max_acceleration: 20.0
linear.x.min_acceleration: -20.0
angular.z.max_velocity: 4.0
angular.z.min_velocity: -4.0
angular.z.max_acceleration: 25.0
angular.z.min_acceleration: -25.0
R100 Ridgeback Controller Defaults:
platform:
extras:
ros_parameters:
platform_velocity_controller:
kinematics.wheels_radius: 0.0759
linear.x.max_velocity: 1.3
linear.x.min_velocity: -1.3
linear.x.max_acceleration: 1.0
linear.x.min_acceleration: -1.0
linear.y.max_velocity: 1.3
linear.y.min_velocity: -1.3
linear.y.max_acceleration: 1.0
linear.y.min_acceleration: -1.0
angular.z.max_velocity: 4.0
angular.z.min_velocity: -4.0
angular.z.max_acceleration: 2.0
angular.z.min_acceleration: -2.0
W200 Warthog Controller Defaults:
platform:
extras:
ros_parameters:
platform_velocity_controller:
wheel_radius: 0.3
linear.x.max_velocity: 5.0
linear.x.min_velocity: -5.0
linear.x.max_acceleration: 50.0
linear.x.min_acceleration: -50.0
angular.z.max_velocity: 4.0
angular.z.min_velocity: -4.0
angular.z.max_acceleration: 40.0
angular.z.min_acceleration: -40.0