Skip to content

Wheel xacro

Pedro Alcantara edited this page Oct 11, 2020 · 6 revisions

Description

The xacro:wheel add a wheel link and joint to the differential robot. The xacro:wheel characteristics:

  • Link name: ${prefix}_wheel.
    The ${prefix} is the value of the prefix parameter that is added to the wheel name. If you set the prefix parameter as front, the name of the link will be front_wheel.
  • Collision: Cylinder.
  • Visual: Simple red cylinder or mesh.
  • Joint name:${prefix}_wheel_joint.
    The joint name follows the same pattern as the link name. If the prefix parameter is set as front, the joint name will be front_wheel_joint.
  • Joint type: revolute.
  • Joint axis: Y-axis.
  • Parent link: base_link.
  • Child link: ${prefix}_wheel.
  • Parameters:
    • prefix [string]: String to be added to the link and joint name.
    • reflect [1/-1]: Value to set the side of the wheel. The value 1, will place the wheel on the positive side of the Y-axis. If it's set as -1, will be placed on the negative side.
    • wheel_props [dictionary]: Dictionary with the properties of the wheel. The dictionary must have these parameters:
      • mass [float]: Link mass in Kilograms.
      • radius [float]: Wheel radius in meters.
      • length [float]: Wheel length, considering the wheel as a cylinder, in meters.
      • x_offset [float]: Offset distance on the X-axis, in meters, from the front outer face of the base to the center of the wheel.
      • y_offset [float]: Offset distance on the Y-axis, in meters, from the outer face of the base to the inner face of the wheel. The outer face of the base is the reference so, if the wheels are inside the base the value must be negative. If the wheels are outside, must be positive.
      • z_offset [float]: Offset distance on the Z-axis, in meters, from the bottom face of the base to the center of the wheel.
    • base_props [dictionary]: Dictionary with the base link properties;
    • mesh [string]: Name of the wheel link mesh. The mesh name should also have the file extension. This parameter has a default value:'' (empty string). With the default value, the link visual is a red cylinder, otherwise, it shows the mesh set in the parameter.

⚠️ The mesh file must be added inside the folder with the robot name, as shown in the package organization. The package_name and robot_name also MUST be set as a global property at the robot description file, as shown here.

Usage

Joint Offset Pattern

The offset distances are used to calculate the position of the joint. The images illustrate what is each offset distance.

With the value of each offset distance, the position of the joint is calculated as:

position_x = (base_size_x / 2) - x_offset
position_y = (base_size_y / 2) + y_offset + (wheel_length / 2)
position_z = z_offset

Usage Examples

These are some examples of how to use the xacro::wheel on your robot description.

<!-- Back Wheels -->
  <xacro:wheel prefix="back_right" reflect="-1"
                      wheel_props="${back_wheel_props}"
                      base_props="${base_props}">                    
  </xacro:wheel>

  <xacro:wheel prefix="back_left" reflect="1"
                      wheel_props="${back_wheel_props}"
                      base_props="${base_props}">
  </xacro:wheel>

  <!-- Front Wheels -->
  <xacro:wheel prefix="front_right" reflect="-1" 
                      wheel_props="${front_wheel_props}"
                      base_props="${base_props}"> 
  </xacro:wheel>

  <xacro:wheel prefix="front_left" reflect="1" 
                      wheel_props="${front_wheel_props}"
                      base_props="${base_props}"> 
  </xacro:wheel>
<!-- Back Wheels -->
  <xacro:wheel prefix="back_right" reflect="-1"
                      wheel_props="${back_wheel_props}"
                      base_props="${base_props}"                    
                      mesh="${back_wheel_props['wheel']['mesh']}">
  </xacro:wheel>

  <xacro:wheel prefix="back_left" reflect="1"
                      wheel_props="${back_wheel_props}"
                      base_props="${base_props}"
                      mesh="${back_wheel_props['wheel']['mesh']}">
  </xacro:wheel>

  <!-- Front Wheels -->
  <xacro:wheel prefix="front_right" reflect="-1" 
                      wheel_props="${front_wheel_props}"
                      base_props="${base_props}"> 
  </xacro:wheel>

  <xacro:wheel prefix="front_left" reflect="1" 
                      wheel_props="${front_wheel_props}"
                      base_props="${base_props}"> 
  </xacro:wheel>

The quimera_robot have different wheels on the front on the back.

Properties YAML File

A flexible way of setting the wheels properties is using YAML config files and import them in your description files. To import this file into your robot description, you can add these lines:

  <xacro:property name="back_wheel_yaml" value="$(find ${package_name})/config/${robot_name}/back_wheel.yaml" />
  <xacro:property name="back_wheel_props" value="${load_yaml(back_wheel_yaml)}"/>

  <xacro:property name="front_wheel_yaml" value="$(find ${package_name})/config/${robot_name}/front_wheel.yaml" />
  <xacro:property name="front_wheel_props" value="${load_yaml(front_wheel_yaml)}"/>

Note that the ${package_name} and ${robot_name} are the values of the global xacro:property that must be set in your description files. After these lines, the back_wheel_props and the front_wheel_props are dictionaries xacro:property that has the properties of each wheel type and can be pass to the wheel_prob parameter of the xacro:wheel. The YAML file should be similar to these that are the config wheel of the quimera_robot:

  • back_wheel.yaml
wheel:
  mass: 1.0            # Wheel mass in Kilograms       
  radius: 0.053        # Wheel radius in meters 
  length: 0.033        # Wheel length in meters, considering it as a cylinder 
  mesh: 'wheel.dae'    # Name of the mesh files. Leave it empty ('') to have a red wheel. 
  x_offset: 0.128      # Offset distance on the x-axis in meters.
  y_offset: -0.052     # Offset distance on the y-axis in meters.
  z_offset: 0.05       # Offset distance on the z-axis in meters.
  • front_wheel.yaml
wheel:
  mass: 0.01        # Wheel mass in Kilograms
  radius: 0.011     # Wheel radius in meters 
  length: 0.006     # Wheel length in meters, considering it as a cylinder.
  mesh: ''          # Name of the mesh files. Leave it empty ('') to have a red wheel.
  x_offset: 0.035   # Offset distance on the x-axis in meters.
  y_offset: -0.056  # Offset distance on the y-axis in meters.
  z_offset: 0.008   # Offset distance on the z-axis in meters.

For more details and references on how to import YAML files and the xacro:property dictionary, see the Xacro Wiki

As described on the config files above, the quimera_robot has a different pair of wheels. The back_wheels are bigger and have mesh while the front_wheels are smaller and it's without mesh, as the image shows.

As described before, the wheel joint rotates around the y-axis. This can be seen in this image, which shows the wheel axis.

Clone this wiki locally