<?xml version="1.0"?>
<robot name="wild_thumper" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="PI" value="3.1415926535897931" />
- <xacro:include filename="$(find hector_sensors_description)/urdf/asus_camera.urdf.xacro" />
<link name="base_footprint">
<visual>
</visual>
</link>
- <xacro:asus_camera name="camera" parent="mounting_plate">
- <origin xyz="0.107 0.0 0.04" rpy="0 0 0"/>
- </xacro:asus_camera>
-
- <link name="sonar_forward">
+ <link name="lidar">
<visual>
<geometry>
- <box size="0.016 0.044 0.02"/>
+ <mesh filename="package://wild_thumper/meshes/rplidar_a2.stl" scale="0.001 0.001 0.001"/>
</geometry>
- <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
- <material name="green">
- <color rgba="0 1 0 0.8"/>
+ <origin xyz="0.0 0.0 ${0.0408/2}" rpy="0 0 0"/>
+ <material name="black">
+ <color rgba="0 0 0 1"/>
</material>
</visual>
</link>
- <link name="sonar_backward">
+ <link name="sonar_forward_left">
<visual>
<geometry>
<box size="0.016 0.044 0.02"/>
</visual>
</link>
- <link name="ir_left">
+ <link name="sonar_forward_right">
<visual>
<geometry>
- <box size="0.015 0.015 0.046"/>
+ <box size="0.016 0.044 0.02"/>
</geometry>
- <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
- <material name="black">
- <color rgba="0 0 0 1"/>
+ <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
+ <material name="green">
+ <color rgba="0 1 0 0.8"/>
</material>
</visual>
</link>
- <link name="ir_right">
+ <link name="sonar_backward">
<visual>
<geometry>
- <box size="0.015 0.015 0.046"/>
+ <box size="0.016 0.044 0.02"/>
</geometry>
- <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
- <material name="black">
- <color rgba="0 0 0 1"/>
+ <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
+ <material name="green">
+ <color rgba="0 1 0 0.8"/>
</material>
</visual>
</link>
<origin xyz="0.06 -0.03 0.058" rpy="0 0 0"/>
</joint>
- <joint name="sonar_forward_joint" type="fixed">
+ <joint name="sonar_forward_left_joint" type="fixed">
<parent link="mounting_plate"/>
- <child link="sonar_forward"/>
- <origin xyz="0.115 0.0 -0.012" rpy="0 0 0"/>
+ <child link="sonar_forward_left"/>
+ <origin xyz="0.115 0.05 -0.012" rpy="0 ${-5*PI/180} 0"/>
</joint>
- <joint name="sonar_backward_joint" type="fixed">
+ <joint name="sonar_forward_right_joint" type="fixed">
<parent link="mounting_plate"/>
- <child link="sonar_backward"/>
- <origin xyz="-0.115 0.0 -0.012" rpy="0 ${PI} 0"/>
+ <child link="sonar_forward_right"/>
+ <origin xyz="0.115 -0.05 -0.012" rpy="0 ${-5*PI/180} 0"/>
</joint>
- <joint name="ir_left_joint" type="fixed">
+ <joint name="sonar_backward_joint" type="fixed">
<parent link="mounting_plate"/>
- <child link="ir_left"/>
- <origin xyz="0.0 ${0.072+0.015} -0.045" rpy="0 0 ${PI/2}"/>
+ <child link="sonar_backward"/>
+ <origin xyz="-0.115 0.0 -0.012" rpy="0 ${-175*PI/180} 0"/>
</joint>
- <joint name="ir_right_joint" type="fixed">
+ <joint name="lidar_joint" type="fixed">
<parent link="mounting_plate"/>
- <child link="ir_right"/>
- <origin xyz="0.0 ${-0.072-0.015} -0.045" rpy="0 0 ${-PI/2}"/>
+ <child link="lidar"/>
+ <origin xyz="0.075 0.01 0.0" rpy="0 0 ${-110*PI/180}"/>
</joint>
<xacro:macro name="wheel" params="pos side xyz rpy">