Skip to content
Snippets Groups Projects
Commit cae3b498 authored by Fernando Herrero's avatar Fernando Herrero
Browse files

Add base_footprint. Remove old odometry dependency

parent 095f2ef7
No related branches found
No related tags found
No related merge requests found
This diff is collapsed.
......@@ -42,7 +42,6 @@
<run_depend>gazebo_ros</run_depend>
<run_depend>gazebo_plugins</run_depend>
<run_depend>hector_gazebo_plugins</run_depend>
<run_depend>odometry</run_depend> <!-- from https://github.com/AutoModelCar/model_car/tree/version-3 -->
<run_depend>imu_filter_madgwick</run_depend>
<!-- Use test_depend for packages you need only for testing: -->
......
......@@ -51,7 +51,7 @@
<gazebo>
<plugin name="model_car_ground_truth" filename="libgazebo_ros_p3d.so">
<frameName>map</frameName>
<bodyName>base_link</bodyName>
<bodyName>base_footprint</bodyName>
<topicName>odom_ground_truth</topicName>
<updateRate>30.0</updateRate>
</plugin>
......
......@@ -7,7 +7,18 @@
<xacro:property name="PI" value="3.1415926535897931" />
<xacro:property name="angle_limit" value="${PI/3.0}" />
<xacro:property name="wheel_radius" value="0.05" />
<link name="base_footprint">
</link>
<joint name="base_footprint_to_base_link" type="fixed">
<origin xyz="0.0 0.0 ${wheel_radius}" rpy="0 0 0" />
<parent link="base_footprint" />
<child link="base_link" />
</joint>
<link name="base_link">
<inertial>
<mass value="0.001" />
......@@ -50,12 +61,12 @@
<!-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ WHEELS ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -->
<!-- ======= REAR LEFT ======= -->
<xacro:wheel name="rear_left" parent="base_link" direction="1.0">
<origin xyz="0 0.108 0" rpy="1.5707 0 3.14159" />
<origin xyz="0 0.108 0" rpy="${PI/2.0} 0 ${PI}" />
</xacro:wheel>
<!-- ======= REAR RIGHT ======= -->
<xacro:wheel name="rear_right" parent="base_link" direction="-1.0">
<origin xyz="0 -0.108 0" rpy="1.5707 0 0" />
<origin xyz="0 -0.108 0" rpy="${PI/2.0} 0 0" />
</xacro:wheel>
<link name="steer_left">
......@@ -91,7 +102,7 @@
<!-- ======= FRONT LEFT ======= -->
<xacro:wheel name="front_left" parent="steer_left" direction="1.0">
<origin xyz="0.0 0.0 0" rpy="1.5707 0 3.14159" />
<origin xyz="0.0 0.0 0" rpy="${PI/2.0} 0 ${PI}" />
</xacro:wheel>
<link name="steer_right">
......@@ -127,7 +138,7 @@
<!-- ======= FRONT RIGHT ======= -->
<xacro:wheel name="front_right" parent="steer_right" direction="-1.0">
<origin xyz="0.0 0.0 0" rpy="1.5707 0 0" />
<origin xyz="0.0 0.0 0" rpy="${PI/2.0} 0 0" />
</xacro:wheel>
</robot>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment