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

How to set LiDAR rotation when using an "included" file?

asked 2020-12-04 07:09:18 -0600

Py gravatar image

I am trying to include 2 LiDAR units in a .xacro file by including the file here twice. Here's the code I use:

<?xml version="1.0"?>
<robot xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
       xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
       xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
       xmlns:xacro="http://www.ros.org/wiki/xacro"
       name="sensors">

  <!-- Front LiDAR  -->

  <xacro:include filename="$(find jackal_description)/urdf/accessories/sick_lms1xx_mount.urdf.xacro" />
  <xacro:sick_lms1xx_mount prefix="$(optenv JACKAL_LASER_MOUNT front)"
                           parent_link="$(optenv JACKAL_LASER_MOUNT front)_mount"
                           topic="$(optenv JACKAL_LASER_TOPIC /front_lidar_scan)"/>

  <!-- Rear LiDAR  -->

  <xacro:include filename="$(find jackal_description)/urdf/accessories/sick_lms1xx_mount.urdf.xacro" />
  <xacro:sick_lms1xx_mount prefix="$(optenv JACKAL_LASER_MOUNT rear)"
                           parent_link="$(optenv JACKAL_LASER_MOUNT rear)_mount"
                           topic="$(optenv JACKAL_LASER_TOPIC /rear_lidar_scan)"/>                           
</robot>

This works but I need one LiDAR unit to be oriented in the opposite direction. In the included file this segment below, it suggests I could set JACKAL_LASER_RPY but I can't work out how to do this from my file above. Could anyone show me how? I've been searching how I might be able to set rpy within the include tags but it seem that this isn't possible.

<joint name="${prefix}_laser_mount_joint" type="fixed">
  <origin xyz="$(optenv JACKAL_LASER_OFFSET 0 0 0)"
          rpy="$(optenv JACKAL_LASER_RPY 0 0 0)" />
  <parent link="${parent_link}" />
  <child link="${prefix}_laser_mount" />
</joint>
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-12-04 10:14:59 -0600

tryan gravatar image

updated 2020-12-04 10:16:24 -0600

The optenv qualifier points to environmental variables as mentioned in the roslaunch documentation. There's no way to set an environmental variable from the include tag AFAIK, but someone can correct me if I'm wrong. In any case, I don't think that would get you the behavior you want. The syntax is $(optenv VARIABLE_NAME default_value), so if the variable is set, it will use that value everywhere. As you're using the lidar macro twice, the variables are used in multiple places and won't have different values.

One option is to leave sick_lms1xx_mount.urdf.xacro alone and put in some "dummy" joints/links to get the orientation you want, which in your case might look similar to this:

# robot, namespace stuff, etc.
...
# Note: you only have to include the lidar macro file (sick_lms1xx_mount.urdf.xacro) once.
<xacro:include filename="$(find jackal_description)/urdf/accessories/sick_lms1xx_mount.urdf.xacro" />

<link name="base_link" />

<joint name="base_front_joint" type="fixed">
  <origin xyz="0.1 0 0" rpy="0 0 0" />  # Puts it 10 cm forward.
  <parent link="base_link" />
  <child link="front_link" />
</joint>

<link name="front_link" />

<xacro:sick_lms1xx_mount prefix="front"
                         parent_link="front_link"
                         topic="front_lidar_scan"/>

<joint name="base_rear_joint" type="fixed">
  <origin xyz="-0.1 0 0" rpy="0 0 ${-pi}" />  # Puts it 10 cm back and spins it 180 deg.
  <parent link="base_link" />
  <child link="rear_link" />
</joint>

<link name="rear_link" />

<xacro:sick_lms1xx_mount prefix="rear"
                         parent_link="rear_link"
                         topic="rear_lidar_scan"/>
...

You may note that there's repetition there, so you could create your own macro for adding the lidar(s), which includes the pose parameters as arguments:

<xacro:include filename="$(find jackal_description)/urdf/accessories/sick_lms1xx_mount.urdf.xacro" />
<xacro:macro name="sick_lm1xx" params="prefix parent topic xyz rpy" />
  <joint name="base_${prefix}_joint" type="fixed">
    <origin xyz="${xyz}" rpy="${rpy}" />  # Puts it 10 cm forward.
    <parent link="${parent}" />
    <child link="${prefix}_link" />
  </joint>

  <link name="${prefix}_link" />

  <xacro:sick_lms1xx_mount prefix="${prefix}"
                           parent_link="${prefix}_link"
                           topic="${topic}"/>
</xacro:macro>

<link name="base_link" />

<xacro:sick_lm1xx prefix="front"
                  parent="base_link"
                  topic="front_lidar_scan"
                  xyz="0.1 0 0"
                  rpy="0 0 0" />

<xacro:sick_lm1xx prefix="rear"
                  parent="base_link"
                  topic="rear_lidar_scan"
                  xyz="-0.1 0 0"
                  rpy="0 0 ${-pi}" />

At this point you may as well write your own version of the original macro with xyz and rpy parameters and use that instead. The source is in the Jackal GitHub repo.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-12-04 07:09:18 -0600

Seen: 463 times

Last updated: Dec 04 '20