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

[gazebo 11] How to set a default variable/parameter in xacro

asked 2023-05-26 14:52:32 -0500

anonymous user

Anonymous

I have a main xacro file where I am calling another xacro as such:

 <xacro:include filename="$(find uuv_gazebo_ros_plugins)/urdf/thruster_snippets.xacro"/>

I have modified the included xacro "thruster_snippets.xacro" so that I can change the size of the thrusters if needed. (sometimes the .dae file is large and therefore needs to be scaled down). The parameter that I added was scale to the "generic_thruster_macro" and the "thruster_module_first_order_basic_fcn_macro".

However, I want to set a default value for scale so that I don't have to include that parameter every time I add a new robot.

Does anyone know how to do this?

This code looks like this:

    <?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

  <!-- ROTOR DYNAMICS MACROS -->

  <!-- First order dynamics -->

  <xacro:macro name="rotor_dyn_first_order_macro" params="time_constant">
    <dynamics>
      <type>FirstOrder</type>
      <timeConstant>${time_constant}</timeConstant>
    </dynamics>
  </xacro:macro>

  <!--
    MACROS FOR CONVERSION FUNCTIONS BETWEEN ROTOR'S ANG. VELOCITY AND
    THRUSTER FORCE
  -->

  <!--
    1) Basic curve
      Input: x
      Output: thrust
      Function: thrust = rotorConstant * x * abs(x)
  -->
  <xacro:macro name="thruster_cf_basic_macro"
    params="rotor_constant">
    <conversion>
      <type>Basic</type>
      <rotorConstant>${rotor_constant}</rotorConstant>
    </conversion>
  </xacro:macro>

  <!--
    2) Dead-zone nonlinearity described in [1]
      [1] Bessa, Wallace Moreira, Max Suell Dutra, and Edwin Kreuzer. "Thruster
          dynamics compensation for the positioning of underwater robotic vehicles
          through a fuzzy sliding mode based approach." ABCM Symposium Series in
          Mechatronics. Vol. 2. 2006.
      Input: x
      Output: thrust
      Function:
        thrust = rotorConstantL * (x * abs(x) - deltaL), if x * abs(x) <= deltaL
        thrust = 0, if deltaL < x * abs(x) < deltaR
        thrust = rotorConstantR * (x * abs(x) - deltaR), if x * abs(x) >= deltaL
  -->
  <xacro:macro name="thruster_cf_dead_zone_macro"
    params="rotor_constant_l
            rotor_constant_r
            delta_l
            delta_r">
    <conversion>
      <type>Bessa</type>
      <rotorConstantL>${rotor_constant_l}</rotorConstantL>
      <rotorConstantR>${rotor_constant_r}</rotorConstantR>
      <deltaL>${delta_l}</deltaL>
      <deltaR>${delta_r}</deltaR>
    </conversion>
  </xacro:macro>

  <!--
    3) Linear interpolation
      If you have access to the thruster's data sheet, for example,
      you can enter samples of the curve's input and output values
      and the thruster output will be found through linear interpolation
      of the given samples.
  -->
  <xacro:macro name="thruster_cf_linear_interp_macro"
    params="input_values
            output_values">
    <conversion>
      <type>LinearInterp</type>
      <inputValues>${input_values}</inputValues>
      <outputValues>${output_values}</outputValues>
    </conversion>
  </xacro:macro>

  <!-- THRUSTER MODULE MACROS  -->

  <xacro:macro name="generic_thruster_macro"
    params="namespace
            thruster_id
            *origin
            mesh_filename
            scale
            *dynamics
            *conversion">
    <joint name="${namespace}/thruster_${thruster_id}_joint" type="continuous">
      <xacro:insert_block name="origin"/>
      <axis xyz="1 0 0"/>
      <parent link="${namespace}/base_link"/>
      <child link="${namespace}/thruster_${thruster_id}"/>
    </joint>

    <link name="${namespace}/thruster_${thruster_id}">
      <xacro:box_inertial x="0" y="0" z="0" mass="0.001">
        <origin xyz="0 0 0" rpy="0 0 0"/>
      </xacro:box_inertial>
      <visual>
        <origin rpy="0 0 0" xyz="0 0 0"/>
        <geometry>
          <mesh filename="${mesh_filename}" scale="${scale}"/>
        </geometry>
      </visual>
      <collision>
        <!-- todo: gazebo needs a collision volume or it will ignore ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2023-05-27 06:46:20 -0500

Mike Scheutzow gravatar image

This is documented in section 7.1 of https://wiki.ros.org/xacro

Example snippet: params="x y:=${2*y} z:=0"

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2023-05-26 14:52:32 -0500

Seen: 196 times

Last updated: May 27 '23