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

Add kinetic sensor to turtlebot3 robot in gazebo

asked 2020-01-22 08:11:15 -0500

ricardo.sutana gravatar image

Hi guys

I`m trying to add a kinect v2 sensor model to turtlebot3 robot.

I download the kinect model from this repository and it work when I launch in gazebo with the command

roslaunch kinect_v2 gazebo.launch

The turtlebot robot was installed by

sudo apt-get install ros-kinetic-turtlebot3*

The simulation is loaded correctly when I launch it by the command:

roslaunch turtlebot3_gazebo turtlebot3_empty_world.launch

The topics from the robot are correctly published

Now, I would like to add the kinect sensor model to the turtlebot3 robot. In the folder /opt/ros/kinetic/share/turtlebot3_description/urdf only has .xacro files. One of then is the turtlebot3_burguer.urdf.xacro which I suppose to be the one to be modified.

<?xml version="1.0" ?>
<robot name="turtlebot3_burger" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find turtlebot3_description)/urdf/common_properties.xacro"/>
  <xacro:include filename="$(find turtlebot3_description)/urdf/turtlebot3_burger.gazebo.xacro"/>

  <link name="base_footprint"/>

  <joint name="base_joint" type="fixed">
    <parent link="base_footprint"/>
    <child link="base_link"/>
    <origin xyz="0.0 0.0 0.010" rpy="0 0 0"/>
  </joint>

  <link name="base_link">
    <visual>
      <origin xyz="-0.032 0 0.0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://turtlebot3_description/meshes/bases/burger_base.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="light_black"/>
    </visual>

    <collision>
      <origin xyz="-0.032 0 0.070" rpy="0 0 0"/>
      <geometry>
        <box size="0.140 0.140 0.143"/>
      </geometry>
    </collision>

    <inertial>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <mass value="8.2573504e-01"/>
      <inertia ixx="2.2124416e-03" ixy="-1.2294101e-05" ixz="3.4938785e-05"
               iyy="2.1193702e-03" iyz="-5.0120904e-06"
               izz="2.0064271e-03" />
    </inertial>
  </link>

  <joint name="wheel_left_joint" type="continuous">
    <parent link="base_link"/>
    <child link="wheel_left_link"/>
    <origin xyz="0.0 0.08 0.023" rpy="-1.57 0 0"/>
    <axis xyz="0 0 1"/>
  </joint>

  <link name="wheel_left_link">
    <visual>
      <origin xyz="0 0 0" rpy="1.57 0 0"/>
      <geometry>
        <mesh filename="package://turtlebot3_description/meshes/wheels/left_tire.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="dark"/>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder length="0.018" radius="0.033"/>
      </geometry>
    </collision>

    <inertial>
      <origin xyz="0 0 0" />
      <mass value="2.8498940e-02" />
      <inertia ixx="1.1175580e-05" ixy="-4.2369783e-11" ixz="-5.9381719e-09"
               iyy="1.1192413e-05" iyz="-1.4400107e-11"
               izz="2.0712558e-05" />
      </inertial>
  </link>

  <joint name="wheel_right_joint" type="continuous">
    <parent link="base_link"/>
    <child link="wheel_right_link"/>
    <origin xyz="0.0 -0.080 0.023" rpy="-1.57 0 0"/>
    <axis xyz="0 0 1"/>
  </joint>

  <link name="wheel_right_link">
    <visual>
      <origin xyz="0 0 0" rpy="1.57 0 0"/>
      <geometry>
        <mesh filename="package://turtlebot3_description/meshes/wheels/right_tire.stl" scale="0.001 0.001 0.001 ...
(more)
edit retag flag offensive close merge delete

Comments

Hi Ricardo! I didn't get your problem: Are you looking for general instructions on how to update a xacro file? Or do you already know how to do it but are getting an error during the xacro parsing? (in which case what is the error?)

vbs gravatar image vbs  ( 2020-01-22 09:18:48 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-01-25 10:15:12 -0500

vbs gravatar image

The URDF tutorials are really good to learn how to create or adapt urdf and xacro files (part 2 should be enough).

But your case seems simpler, as you already have both of the URDF definitions that you need. You should be able to mostly just replicate the example code given in the kinect_v2_standalone.urdf.xacro.

More specifically, you would modify the xacro file that you posted above to include:

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

.
.
.

<xacro:kinect_v2  parent="base_link">
        <origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:kinect_v2>

Modifying the desired relative pose of the camera accordingly ('origin' tag above).

edit flag offensive delete link more

Comments

Thank you VBS It not worked for turtlebot3, but works perfectly for husky A200 robot which is the simulation that I really need. I owe you a beer!

ricardo.sutana gravatar image ricardo.sutana  ( 2020-01-29 12:29:50 -0500 )edit

Great, glad I could help! PS: if you think the answer is correct, click the check button near it so others can more easily find it :)

vbs gravatar image vbs  ( 2020-01-29 12:55:29 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-01-22 08:11:15 -0500

Seen: 1,019 times

Last updated: Jan 25 '20