Skip to content

Commit

Permalink
Simulation using gazebo_ros_force_based_move.
Browse files Browse the repository at this point in the history
  • Loading branch information
mikepurvis committed Jan 18, 2016
1 parent 68bf894 commit a814017
Show file tree
Hide file tree
Showing 6 changed files with 61 additions and 81 deletions.
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
*.swp
.DS_Store
60 changes: 0 additions & 60 deletions ridgeback_description/urdf/.gazebo

This file was deleted.

2 changes: 1 addition & 1 deletion ridgeback_description/urdf/accessories.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
ridgeback_base/launch/base.launch
-->

<xacro:include filename="accessories/sick_lms1xx_mount.urdf.xacro" />
<xacro:include filename="$(find ridgeback_description)/urdf/accessories/sick_lms1xx_mount.urdf.xacro" />

<!-- If enabled, generate the front LASER payload (by default enabled and a SICK LMS111). -->
<xacro:if value="$(optenv RIDGEBACK_FRONT_SICK_LASER 0)">
Expand Down
51 changes: 43 additions & 8 deletions ridgeback_description/urdf/ridgeback.gazebo
Original file line number Diff line number Diff line change
@@ -1,14 +1,17 @@
<?xml version="1.0"?>
<robot>

<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/</robotNamespace>
</plugin>
</gazebo>

<!--
<gazebo>
<plugin name="gazebo_ros_force_based_move" filename="libgazebo_ros_force_based_move.so">
<robotBaseFrame>base_link</robotBaseFrame>

<!-- Don't publish a transform: the controller does it. -->
<publishOdometryTf>0</publishOdometryTf>
</plugin>

<plugin name="imu_controller" filename="libhector_gazebo_ros_imu.so">
<robotNamespace>/</robotNamespace>
<updateRate>50.0</updateRate>
Expand All @@ -21,34 +24,66 @@
<headingDrift>0.005</headingDrift>
<headingGaussianNoise>0.005</headingGaussianNoise>
</plugin>
</gazebo>
-->
<gazebo>

<plugin name="gazebo_ros_joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
<jointName>front_rocker</jointName>
<robotNamespace>/</robotNamespace>
<updateRate>50.0</updateRate>
</plugin>
</gazebo>

<!-- All static links get collapsed down to base_link in Gazebo, so that's
the one to apply the colour to. -->
the one to apply the colour to (in Gazebo 5+). -->
<gazebo reference="base_link">
<material>Gazebo/DarkGrey</material>
<gravity>true</gravity>
</gazebo>

<!-- Individual link colouring still needed in Gazebo 2.x -->
<gazebo reference="chassis_link"><material>Gazebo/DarkGrey</material></gazebo>
<gazebo reference="top_link"><material>Gazebo/DarkGrey</material></gazebo>
<gazebo reference="front_cover_link"><material>Gazebo/DarkGrey</material></gazebo>
<gazebo reference="rear_cover_link"><material>Gazebo/DarkGrey</material></gazebo>

<!-- Wheel friction to zero, as movement is handled by applying forces at
the body level. -->
<gazebo reference="front_left_wheel_link">
<material>Gazebo/DarkGrey</material>
<mu1>0.0</mu1>
</gazebo>

<gazebo reference="front_right_wheel_link">
<material>Gazebo/DarkGrey</material>
<mu1>0.0</mu1>
</gazebo>

<gazebo reference="rear_left_wheel_link">
<material>Gazebo/DarkGrey</material>
<mu1>0.0</mu1>
</gazebo>

<gazebo reference="rear_right_wheel_link">
<material>Gazebo/DarkGrey</material>
<mu1>0.0</mu1>
</gazebo>

<!-- This is an wheel-level solution to possibly revisit at a future date. -->
<!--<gazebo>
<plugin name="mecanum_gazebo" filename="libmecanum_force_plugin.so">
<wheelJointName>front_left_wheel</wheelJointName>
<forceScaleFactor>1</forceScaleFactor>
</plugin>
<plugin name="mecanum_gazebo" filename="libmecanum_force_plugin.so">
<wheelJointName>front_right_wheel</wheelJointName>
<forceScaleFactor>-1</forceScaleFactor>
</plugin>
<plugin name="mecanum_gazebo" filename="libmecanum_force_plugin.so">
<wheelJointName>rear_left_wheel</wheelJointName>
<forceScaleFactor>-1</forceScaleFactor>
</plugin>
<plugin name="mecanum_gazebo" filename="libmecanum_force_plugin.so">
<wheelJointName>rear_right_wheel</wheelJointName>
<forceScaleFactor>1</forceScaleFactor>
</plugin>
</gazebo> -->
</robot>
27 changes: 15 additions & 12 deletions ridgeback_description/urdf/ridgeback.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
<xacro:property name="chassis_length" value="0.935" />
<xacro:property name="chassis_width" value="0.787" />
<xacro:property name="chassis_height" value="0.216" />
<xacro:property name="deck_height" value="0.280" />

<xacro:property name="axle_offset" value="0.0500" />
<xacro:property name="rocker_offset" value="0.301525" />
Expand All @@ -24,7 +25,7 @@
<material name="yellow"><color rgba="0.8 0.8 0.0 1.0" /></material>
<material name="black"><color rgba="0.15 0.15 0.15 1.0" /></material>

<xacro:macro name="wheel" params="prefix side y_friction *joint_pose">
<xacro:macro name="wheel" params="prefix side *joint_pose">
<link name="${prefix}_${side}_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
Expand Down Expand Up @@ -95,11 +96,11 @@
<xacro:insert_block name="joint_limits" />
</joint>

<xacro:wheel prefix="${prefix}" side="left" y_friction="-0.707107">
<xacro:wheel prefix="${prefix}" side="left">
<origin xyz="0 ${rocker_width/2 + wheel_width/2} 0" rpy="0 0 0" />
</xacro:wheel>
<xacro:wheel prefix="${prefix}" side="right" y_friction="0.707107">
<origin xyz="0 ${-rocker_width/2 - wheel_width/2} 0" rpy="0 0 0" />
<xacro:wheel prefix="${prefix}" side="right">
<origin xyz="0 ${-(rocker_width/2 + wheel_width/2)} 0" rpy="0 0 0" />
</xacro:wheel>
</xacro:macro>

Expand Down Expand Up @@ -128,7 +129,7 @@
<material name="black" />
</visual>
<collision>
<origin xyz="0 0 ${chassis_height/2}"/>
<origin xyz="0 0 ${chassis_height/2}"/>
<geometry>
<box size="${chassis_length} ${chassis_width} ${chassis_height}"/>
</geometry>
Expand Down Expand Up @@ -207,11 +208,6 @@
</visual>
</link>


<!-- TODO: Make this internal_imu_link or something, and use a mixed-in xacro
to supply the joint between it and imu_link. This is important so that imu_link
always points to the "active" IMU. When an upgrade IMU is connected, the
internal_imu_link should remain, but imu_link should point to the upgrade one. -->
<link name="imu_link">
<inertial>
<mass value="0.001"/>
Expand All @@ -224,13 +220,20 @@
<child link="imu_link" />
</joint>

<link name="mid_mount" />
<joint name="mid_mount_joint" type="fixed">
<parent link="base_link" />
<child link="mid_mount" />
<origin xyz="0 0 ${deck_height}" rpy="0 0 0"/>
</joint>

<!-- Bring in simulation data for Gazebo. -->
<xacro:include filename="ridgeback.gazebo" />
<xacro:include filename="$(find ridgeback_description)/urdf/ridgeback.gazebo" />

<!-- Optional standard accessories, including their simulation data. The rendering
of these into the final description is controlled by optenv variables, which
default each one to off.-->
<xacro:include filename="accessories.urdf.xacro" />
<xacro:include filename="$(find ridgeback_description)/urdf/accessories.urdf.xacro" />

<!-- Optional custom includes. -->
<!--<xacro:include filename="$(optenv RIDGEBACK_URDF_EXTRAS empty.urdf)" />-->
Expand Down
Empty file.

0 comments on commit a814017

Please sign in to comment.