ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

So you have a couple options.

1 Use <xacro:arg/> tags to allow passing in arguments via xacro. This Answer explains that process.

2 You can also load a yaml file as a dictionary that can be accessed within a xacro. This allows you to put all your variables in a single file, and load it as a single argument to the xacro (as compared to having an argument for every variable you want to set). Then to change configurations, just load a different yaml.

For an example of this method, consider a package with the following structure:

test_pkg
|-- launch
|   |-- description.launch
|-- params
|   |-- parameters.yaml
|-- xacro
    |-- test_model.xacro

description.launch

<?xml version="1.0"?>
<launch>
<!-- Build the robot description for a xacro and parameter(yaml) file, serve it up for consumption -->
<!-- Note: params_path will be passed into the xacro and accessible as a dictionary for procedural generation of model features -->

<arg name="model_path" default="$(find test_pkg)/xacro/test_model.xacro"/> 
<arg name="params_path" default="$(find test_pkg)/params/parameters.yaml"/> 

<!-- Load the robot_description on the ROS param server using xacro to generate the model description -->
<param name="robot_description" command="$(find xacro)/xacro $(arg model_path) params_path:=$(arg params_path) " />

<!-- Start nodes for serving the model description and joint states-->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />

</launch>

parameters.yaml

name: 'center'

position:
  x: 0
  y: 0
  z: 5

tire:
  mass: 1.0
  width: 0.5
  radius: 0.75

test_model.xacro

<?xml version="1.0"?>
<robot name="test_model" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <!-- This is the top level xacro for generating a model from a parameter file -->

  <!-- Arg: params_path - The path to the parameter (yaml) file -->

  <xacro:property name="PI" value="3.1415926535897931" />

  <!-- 
    Kinda stupid way to import external parameters, open to better options.

    The xacro:arg "params_path" exposes the arg to launch file.

    The xacro:property "params_path" is required to get the evaluated 
      symbol into xacro before "load_yaml"

    The xacro:proterty "mp" (which stands for "model parameters") gets the 
      dictionary from "params_path" and is accessed using ${mp['key_name']} 
      which will evaluate to the key value

    The xacro:arg and xacro:property "params_path" shares a name but does 
      not seem to clobber eachother.
    They are not required to have the same name, it was just convenient
  -->

  <!-- Need argument to get from launch file -->
  <xacro:arg name="params_path" default="../params/parameters.yaml"/> 

  <!-- Need seperate property for xacro inorder processing -->
  <xacro:property name="params_path" value="$(arg params_path)"/> 

  <!-- Read in the yaml dict as mp (short for model parameters) -->
  <xacro:property name="mp" value="${load_yaml(params_path)}"/> 


  <!-- Required Base Link -->
  <link name="base_link"/>

  <!-- A body to act as a stand -->
  <link name="body_link">
    <visual name="visual">
      <geometry>
        <box size="1 1 0.5"/>
      </geometry>
    </visual>
  </link>

  <!-- A joint to connect the body to the base_link -->
  <joint name="body_joint" type="fixed">
    <origin xyz="0 0 0.25" rpy="0 0 0" />
    <parent link="base_link"/>
    <child link="body_link"/>
  </joint>


  <!-- A wheel that is generated using parameters in an external yaml -->
  <link name="${mp['name']}_link">
    <visual>
      <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}"/>
      <geometry>
        <cylinder length="${mp['tire']['width']}" radius="${mp['tire']['radius']}"/> 
      </geometry>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}"/>
      <geometry>
        <cylinder length="${mp['tire']['width']}" radius="${mp['tire']['radius']}"/> 
      </geometry>
    </collision>

    <inertial>
      <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}"/>
      <mass value="${mp['tire']['mass']}"/>
      <inertia
        ixx="${(1/12) * mp['tire']['mass'] * (3 * mp['tire']['radius'] * mp['tire']['radius'] + mp['tire']['width'] * mp['tire']['width']) }" 
        ixy="0.0" 
        ixz="0.0"
        iyy="${(1/12) * mp['tire']['mass'] * (3 * mp['tire']['radius'] * mp['tire']['radius'] + mp['tire']['width'] * mp['tire']['width']) }"
        iyz="0.0"
        izz="${(1/2) * mp['tire']['mass'] * mp['tire']['radius'] * mp['tire']['radius']}"/>
    </inertial>
  </link>

  <!-- A joint to connect the wheel to the base_link -->
  <joint name="${mp['name']}_joint" type="fixed">
    <origin xyz="${mp['position']['x']} ${mp['position']['y']} ${mp['position']['z']}" 
            rpy="0 0 0"/>
    <parent link="base_link"/>
    <child link="${mp['name']}_link"/>
  </joint>

</robot>

Hope this helps!

So you have a couple options.

1 EDIT: I didn't see tryan answer while I was writing, they explain this first option... Use <xacro:arg/> tags to allow passing in arguments via xacro. This Answer explains that process.process.

2 You can also load a yaml file as a dictionary that can be accessed within a xacro. This allows you to put all your variables in a single file, and load it as a single argument to the xacro (as compared to having an argument for every variable you want to set). Then to change configurations, just load a different yaml.

For an example of this method, consider a package with the following structure:

test_pkg
|-- launch
|   |-- description.launch
|-- params
|   |-- parameters.yaml
|-- xacro
    |-- test_model.xacro

description.launch

<?xml version="1.0"?>
<launch>
<!-- Build the robot description for a xacro and parameter(yaml) file, serve it up for consumption -->
<!-- Note: params_path will be passed into the xacro and accessible as a dictionary for procedural generation of model features -->

<arg name="model_path" default="$(find test_pkg)/xacro/test_model.xacro"/> 
<arg name="params_path" default="$(find test_pkg)/params/parameters.yaml"/> 

<!-- Load the robot_description on the ROS param server using xacro to generate the model description -->
<param name="robot_description" command="$(find xacro)/xacro $(arg model_path) params_path:=$(arg params_path) " />

<!-- Start nodes for serving the model description and joint states-->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />

</launch>

parameters.yaml

name: 'center'

position:
  x: 0
  y: 0
  z: 5

tire:
  mass: 1.0
  width: 0.5
  radius: 0.75

test_model.xacro

<?xml version="1.0"?>
<robot name="test_model" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <!-- This is the top level xacro for generating a model from a parameter file -->

  <!-- Arg: params_path - The path to the parameter (yaml) file -->

  <xacro:property name="PI" value="3.1415926535897931" />

  <!-- 
    Kinda stupid way to import external parameters, open to better options.

    The xacro:arg "params_path" exposes the arg to launch file.

    The xacro:property "params_path" is required to get the evaluated 
      symbol into xacro before "load_yaml"

    The xacro:proterty "mp" (which stands for "model parameters") gets the 
      dictionary from "params_path" and is accessed using ${mp['key_name']} 
      which will evaluate to the key value

    The xacro:arg and xacro:property "params_path" shares a name but does 
      not seem to clobber eachother.
    They are not required to have the same name, it was just convenient
  -->

  <!-- Need argument to get from launch file -->
  <xacro:arg name="params_path" default="../params/parameters.yaml"/> 

  <!-- Need seperate property for xacro inorder processing -->
  <xacro:property name="params_path" value="$(arg params_path)"/> 

  <!-- Read in the yaml dict as mp (short for model parameters) -->
  <xacro:property name="mp" value="${load_yaml(params_path)}"/> 


  <!-- Required Base Link -->
  <link name="base_link"/>

  <!-- A body to act as a stand -->
  <link name="body_link">
    <visual name="visual">
      <geometry>
        <box size="1 1 0.5"/>
      </geometry>
    </visual>
  </link>

  <!-- A joint to connect the body to the base_link -->
  <joint name="body_joint" type="fixed">
    <origin xyz="0 0 0.25" rpy="0 0 0" />
    <parent link="base_link"/>
    <child link="body_link"/>
  </joint>


  <!-- A wheel that is generated using parameters in an external yaml -->
  <link name="${mp['name']}_link">
    <visual>
      <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}"/>
      <geometry>
        <cylinder length="${mp['tire']['width']}" radius="${mp['tire']['radius']}"/> 
      </geometry>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}"/>
      <geometry>
        <cylinder length="${mp['tire']['width']}" radius="${mp['tire']['radius']}"/> 
      </geometry>
    </collision>

    <inertial>
      <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}"/>
      <mass value="${mp['tire']['mass']}"/>
      <inertia
        ixx="${(1/12) * mp['tire']['mass'] * (3 * mp['tire']['radius'] * mp['tire']['radius'] + mp['tire']['width'] * mp['tire']['width']) }" 
        ixy="0.0" 
        ixz="0.0"
        iyy="${(1/12) * mp['tire']['mass'] * (3 * mp['tire']['radius'] * mp['tire']['radius'] + mp['tire']['width'] * mp['tire']['width']) }"
        iyz="0.0"
        izz="${(1/2) * mp['tire']['mass'] * mp['tire']['radius'] * mp['tire']['radius']}"/>
    </inertial>
  </link>

  <!-- A joint to connect the wheel to the base_link -->
  <joint name="${mp['name']}_joint" type="fixed">
    <origin xyz="${mp['position']['x']} ${mp['position']['y']} ${mp['position']['z']}" 
            rpy="0 0 0"/>
    <parent link="base_link"/>
    <child link="${mp['name']}_link"/>
  </joint>

</robot>

Hope this helps!