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

Is your end goal to use xacro for your robot_state_publisher at runtime? Xacro actually has a function (load_yaml()) that allows you to read in a yaml from a file path. In this case you can hand the path of the file through your xacro call using the xacro_arg_name:=param_to_pass notation. If you are running Galactic or later here is how I would do it (with launch configurations for full runtime flexibility):

Launch File:

#!/usr/bin/env python3

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, LogInfo
from launch.substitutions import LaunchConfiguration, Command, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.descriptions import ParameterValue
from launch_ros.substitutions import FindPackageShare

def generate_launch_description():
  this_pkg = FindPackageShare('test_package')

  model_path = LaunchConfiguration('model_path')
  params_path = LaunchConfiguration('params_path')

  return LaunchDescription([
    DeclareLaunchArgument(
      'model_path',
      default_value=PathJoinSubstitution([this_pkg,'xacro','model.xacro']),
      description='Full path to model xacro file including filename and extension'
    ),

    DeclareLaunchArgument(
      'params_path',
      default_value=PathJoinSubstitution([this_pkg,'params','model.yaml']),
      description='Full path to parameter yaml file including filename and extension'
    ),        

    Node(
      package='robot_state_publisher',
      executable='robot_state_publisher',
      name='robot_state_publisher',
      output='screen',
      parameters=[{
        'robot_description': ParameterValue(Command(['xacro ',model_path,' params_path:=',params_path]), value_type=str)
      }],
    )

  ])

Xacro File: model.xacro

<?xml version="1.0"?>
<robot name="model" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <!-- 
    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
  -->
  <xacro:arg name="params_path" default=""/> <!-- Need argument to get from launch file -->
  <xacro:property name="params_path" value="$(arg params_path)"/> <!-- Need seperate property for xacro inorder processing -->
  <xacro:property name="mp" value="${load_yaml(params_path)}"/> <!-- Read in the yaml dict as mp (short for model parameters) -->


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

  <xacro:property name="wheel_mass" value="${mp['wheel_mass']}"/>
  <xacro:property name="wheel_width" value="${mp['wheel_width']}"/>
  <xacro:property name="wheel_radius" value="${mp['wheel_radius']}"/>


  <link name="base_link"/>

  <link name="body_link">
    <!-- Visual box geometry -->
    <visual name="visual">
      <geometry>
        <box size="1 1 0.5"/>
      </geometry>
    </visual>

    <!-- Collision box geometry-->
    <collision name="collision">
      <geometry>
        <box size="1 1 0.5"/>
      </geometry>
    </collision>

    <!-- Inertia for a box -->
    <inertial>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <mass value="1645.0"/>
      <inertia
          ixx="${(1.0/12.0) * 1645.0 * ( 1 * 1 + 0.5 * 0.5 )}"  
          ixy="0" 
          ixz="0" 
          iyy="${(1.0/12.0) * 1645.0 * ( 1 * 1 + 0.5 * 0.5 )}"  
          iyz="0" 
          izz="${(1.0/12.0) * 1645.0 * ( 1 * 1 + 1 * 1 )}" /> 
    </inertial>
  </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>

  <link name="axle_link">
    <inertial>
      <!-- Pose -->
      <origin xyz="0 0 0" rpy="0 0 0"/>

      <!-- Dummy Mass -->
      <mass value="10.0"/>

      <!-- Dummy Inertia Sphere -->
      <inertia
          ixx="${(2.0/5.0) * 10.0 * 0.1 * 0.1}"  
          ixy="0" 
          ixz="0" 
          iyy="${(2.0/5.0) * 10.0 * 0.1 * 0.1}"  
          iyz="0" 
          izz="${(2.0/5.0) * 10.0 * 0.1 * 0.1}"  /> 
    </inertial>
  </link>

  <joint name="axle_joint" type="fixed">
    <origin xyz="0 0 2.0" rpy="0 0 0"/>
    <parent link="body_link"/>
    <child link="axle_link"/>
  </joint>

  <link name="wheel_link">
    <visual>
      <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}"/>
      <geometry>
        <cylinder length="${wheel_width}" radius="${wheel_radius}"/> 
      </geometry>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}"/>
      <geometry>
        <cylinder length="${wheel_width}" radius="${wheel_radius}"/> 
      </geometry>
    </collision>

    <inertial>
      <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}"/>
      <mass value="${wheel_mass}"/>
      <inertia
        ixx="${(1/12) * wheel_mass * (3 * wheel_radius * wheel_radius + wheel_width * wheel_width) }" 
        ixy="0.0" 
        ixz="0.0"
        iyy="${(1/12) * wheel_mass * (3 * wheel_radius * wheel_radius + wheel_width * wheel_width) }"
        iyz="0.0"
        izz="${(1/2) * wheel_mass * wheel_radius * wheel_radius}"/>
    </inertial>
  </link>

  <joint name="wheel_joint" type="fixed">
    <origin xyz="0 0.25 0" rpy="0 0 0" />
    <parent link="axle_link"/>
    <child link="wheel_link"/>
    <axis xyz="0 1 0" rpy="0 0 0 "/>
  </joint>
</robot>

YAML File: model.yaml

wheel_mass: 10.0
wheel_width: 0.25
wheel_radius: 0.5

Is your end goal to use xacro for your robot_state_publisher at runtime? Xacro actually has a function (load_yaml()) that allows you to read in a yaml from a file path. In this case you can hand the path of the file through your xacro call using the xacro_arg_name:=param_to_pass notation. If you are running Galactic or later here is how I would do it (with launch configurations for full runtime flexibility):

EDIT:

For foxy you may need to use an opaque functions as described in the second answer of this question

Launch File:

#!/usr/bin/env python3

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, LogInfo
from launch.substitutions import LaunchConfiguration, Command, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.descriptions import ParameterValue
from launch_ros.substitutions import FindPackageShare

def generate_launch_description():
  this_pkg = FindPackageShare('test_package')

  model_path = LaunchConfiguration('model_path')
  params_path = LaunchConfiguration('params_path')

  return LaunchDescription([
    DeclareLaunchArgument(
      'model_path',
      default_value=PathJoinSubstitution([this_pkg,'xacro','model.xacro']),
      description='Full path to model xacro file including filename and extension'
    ),

    DeclareLaunchArgument(
      'params_path',
      default_value=PathJoinSubstitution([this_pkg,'params','model.yaml']),
      description='Full path to parameter yaml file including filename and extension'
    ),        

    Node(
      package='robot_state_publisher',
      executable='robot_state_publisher',
      name='robot_state_publisher',
      output='screen',
      parameters=[{
        'robot_description': ParameterValue(Command(['xacro ',model_path,' params_path:=',params_path]), value_type=str)
      }],
    )

  ])

Xacro File: model.xacro

<?xml version="1.0"?>
<robot name="model" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <!-- 
    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
  -->
  <xacro:arg name="params_path" default=""/> <!-- Need argument to get from launch file -->
  <xacro:property name="params_path" value="$(arg params_path)"/> <!-- Need seperate property for xacro inorder processing -->
  <xacro:property name="mp" value="${load_yaml(params_path)}"/> <!-- Read in the yaml dict as mp (short for model parameters) -->


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

  <xacro:property name="wheel_mass" value="${mp['wheel_mass']}"/>
  <xacro:property name="wheel_width" value="${mp['wheel_width']}"/>
  <xacro:property name="wheel_radius" value="${mp['wheel_radius']}"/>


  <link name="base_link"/>

  <link name="body_link">
    <!-- Visual box geometry -->
    <visual name="visual">
      <geometry>
        <box size="1 1 0.5"/>
      </geometry>
    </visual>

    <!-- Collision box geometry-->
    <collision name="collision">
      <geometry>
        <box size="1 1 0.5"/>
      </geometry>
    </collision>

    <!-- Inertia for a box -->
    <inertial>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <mass value="1645.0"/>
      <inertia
          ixx="${(1.0/12.0) * 1645.0 * ( 1 * 1 + 0.5 * 0.5 )}"  
          ixy="0" 
          ixz="0" 
          iyy="${(1.0/12.0) * 1645.0 * ( 1 * 1 + 0.5 * 0.5 )}"  
          iyz="0" 
          izz="${(1.0/12.0) * 1645.0 * ( 1 * 1 + 1 * 1 )}" /> 
    </inertial>
  </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>

  <link name="axle_link">
    <inertial>
      <!-- Pose -->
      <origin xyz="0 0 0" rpy="0 0 0"/>

      <!-- Dummy Mass -->
      <mass value="10.0"/>

      <!-- Dummy Inertia Sphere -->
      <inertia
          ixx="${(2.0/5.0) * 10.0 * 0.1 * 0.1}"  
          ixy="0" 
          ixz="0" 
          iyy="${(2.0/5.0) * 10.0 * 0.1 * 0.1}"  
          iyz="0" 
          izz="${(2.0/5.0) * 10.0 * 0.1 * 0.1}"  /> 
    </inertial>
  </link>

  <joint name="axle_joint" type="fixed">
    <origin xyz="0 0 2.0" rpy="0 0 0"/>
    <parent link="body_link"/>
    <child link="axle_link"/>
  </joint>

  <link name="wheel_link">
    <visual>
      <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}"/>
      <geometry>
        <cylinder length="${wheel_width}" radius="${wheel_radius}"/> 
      </geometry>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}"/>
      <geometry>
        <cylinder length="${wheel_width}" radius="${wheel_radius}"/> 
      </geometry>
    </collision>

    <inertial>
      <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}"/>
      <mass value="${wheel_mass}"/>
      <inertia
        ixx="${(1/12) * wheel_mass * (3 * wheel_radius * wheel_radius + wheel_width * wheel_width) }" 
        ixy="0.0" 
        ixz="0.0"
        iyy="${(1/12) * wheel_mass * (3 * wheel_radius * wheel_radius + wheel_width * wheel_width) }"
        iyz="0.0"
        izz="${(1/2) * wheel_mass * wheel_radius * wheel_radius}"/>
    </inertial>
  </link>

  <joint name="wheel_joint" type="fixed">
    <origin xyz="0 0.25 0" rpy="0 0 0" />
    <parent link="axle_link"/>
    <child link="wheel_link"/>
    <axis xyz="0 1 0" rpy="0 0 0 "/>
  </joint>
</robot>

YAML File: model.yaml

wheel_mass: 10.0
wheel_width: 0.25
wheel_radius: 0.5