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

Passing outside parameters into .urdf file using xacro

asked 2021-05-26 10:14:49 -0600

ghelfrich gravatar image

I have a robot with multiple configurations that have variable link lengths. Instead of editing the .urdf file's parameter definitions each time, is there a way to specify an argument or parameter outside of the .urdf file that is then passed into the .urdf file and used to define the robot geometry?

I am using Melodic on Ubuntu 18.04

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2021-05-27 09:00:02 -0600

tryan gravatar image

As stated in the Xacro wiki, you can use an xacro:arg the same as an arg in a launch file. Your Xacro file may look something like this:

<xacro:arg name="link1_length" default="1.0"/>

<link ...>
  ...
    <cylinder length="$(arg link1_length)" radius="0.2" />
  ...
</link>

Then, in your launch file:

<param name="robot_description" command="$(find xacro)/xacro robot_model.urdf.xacro link1_length:=1.5" />

This answer to #q282902 shows another example.

edit flag offensive delete link more
1

answered 2021-05-27 10:40:34 -0600

djchopp gravatar image

updated 2021-05-27 10:47:46 -0600

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.

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 ...
(more)
edit flag offensive delete link more

Comments

Thank you, this is exactly what I was looking for.

ghelfrich gravatar image ghelfrich  ( 2021-06-01 08:28:42 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2021-05-26 10:07:06 -0600

Seen: 1,707 times

Last updated: May 27 '21