]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
added gazebo simulation
authorErik Andresen <erik@vontaene.de>
Thu, 3 Sep 2015 10:27:59 +0000 (12:27 +0200)
committerErik Andresen <erik@vontaene.de>
Thu, 3 Sep 2015 10:27:59 +0000 (12:27 +0200)
.gitignore
launch/gazebo.launch [new file with mode: 0644]
launch/model.launch [new file with mode: 0644]
meshes/wheel_left.stl [new file with mode: 0644]
meshes/wheel_right.stl [new file with mode: 0644]
meshes/wild_thumper_4wd.blend
meshes/wild_thumper_4wd.stl
urdf/wild_thumper.urdf.xacro
worlds/test.world [new file with mode: 0644]

index b94898552f738567566d1b31b1b67895491613b2..17f5faa0185573ab3fb16d4a009b17c9f68edae0 100644 (file)
@@ -1,2 +1,3 @@
 *.swp
 *.pyc
+*.blend1
diff --git a/launch/gazebo.launch b/launch/gazebo.launch
new file mode 100644 (file)
index 0000000..219529a
--- /dev/null
@@ -0,0 +1,18 @@
+<?xml version="1.0"?>
+<launch>
+       <include file="$(find gazebo_ros)/launch/empty_world.launch" >
+               <arg name="world_name" value="$(find wild_thumper)/worlds/test.world" />
+               <arg name="gui" value="false" />
+       </include>
+
+       <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
+
+       <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen"/>
+
+       <!-- Spawn a robot into Gazebo -->
+       <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model wild_thumper" output="screen" />
+
+       <node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="depthimage_to_laserscan" output="screen">
+               <remap from="/image" to="/camera/depth/image_raw"/>
+        </node>
+</launch>
diff --git a/launch/model.launch b/launch/model.launch
new file mode 100644 (file)
index 0000000..8e4079b
--- /dev/null
@@ -0,0 +1,9 @@
+<?xml version="1.0"?>
+<launch>
+       <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
+
+       <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen"/>
+
+       <!-- Spawn a robot into Gazebo -->
+       <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model wild_thumper" />
+</launch>
diff --git a/meshes/wheel_left.stl b/meshes/wheel_left.stl
new file mode 100644 (file)
index 0000000..a5cceb3
Binary files /dev/null and b/meshes/wheel_left.stl differ
diff --git a/meshes/wheel_right.stl b/meshes/wheel_right.stl
new file mode 100644 (file)
index 0000000..9a46afc
Binary files /dev/null and b/meshes/wheel_right.stl differ
index 7b0039f5eece7b6ca3d0dfcf38ba76159d2e4b6a..7d886fb8ffd489829884458c0cf6423045b8d776 100644 (file)
Binary files a/meshes/wild_thumper_4wd.blend and b/meshes/wild_thumper_4wd.blend differ
index eac11db2733f8d30149c74899cef05fa40ec0de2..a247f71af429ed0d05ea3219fbc61ac0ebbd8ca4 100644 (file)
Binary files a/meshes/wild_thumper_4wd.stl and b/meshes/wild_thumper_4wd.stl differ
index 67e6da7b5602ac6cc180dc406161b34e520c217a..cf2c67240b9edfe7806f2ac61bb31149f23216da 100644 (file)
@@ -1,26 +1,34 @@
 <?xml version="1.0"?>
-<robot name="r2" xmlns:xacro="http://ros.org/wiki/xacro">
+<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_link">
+       <link name="base_footprint">
                <visual>
-                       <origin xyz="0 0 -0.13" rpy="0 0 0"/>
                        <geometry>
-                               <mesh filename="package://wild_thumper/meshes/wild_thumper_4wd.stl" scale="1 1 1" />
+                               <box size="0.28 0.31 0.0"/>
                        </geometry>
+                       <material name="grey">
+                               <color rgba="0.5 0.5 0.5 0.5"/>
+                       </material>
                </visual>
        </link>
 
-       <link name="base_footprint">
+       <link name="base_link">
+               <collision>
+                       <geometry>
+                               <box size="0.23 0.18 0.09"/>
+                       </geometry>
+               </collision>
                <visual>
                        <geometry>
-                               <box size="0.28 0.31 0.0"/>
+                               <mesh filename="package://wild_thumper/meshes/wild_thumper_4wd.stl" />
                        </geometry>
-                       <material name="grey">
-                               <color rgba="0.5 0.5 0.5 0.5"/>
-                       </material>
                </visual>
+               <inertial>
+                       <mass value="1.9"/>
+                       <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
+               </inertial>
        </link>
 
        <link name="base_imu_link">
                </visual>
        </link>
 
-       <xacro:asus_camera name="camera" parent="base_link">
+       <link name="mounting_plate">
+               <visual>
+                       <geometry>
+                               <box size="0.23 0.12 0.001"/>
+                       </geometry>
+               </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>
 
                </visual>
        </link>
 
-       <joint name="imu_joint" type="fixed">
-               <parent link="base_link"/>
-               <child link="base_imu_link"/>
-               <origin xyz="0.06 -0.03 0.058" rpy="0 0 0"/>
-       </joint>
-
        <joint name="base_link_joint" type="fixed">
                <parent link="base_footprint"/>
                <child link="base_link"/>
-               <origin xyz="0.0 0.0 0.13" rpy="0 0 0"/>
+               <origin xyz="0.0 0.0 0.082" rpy="0 0 0"/>
        </joint>
 
-       <joint name="sonar_forward_joint" type="fixed">
+       <joint name="mounting_plate_joint" type="fixed">
                <parent link="base_link"/>
+               <child link="mounting_plate"/>
+               <origin xyz="0.0 0.0 0.044" rpy="0 0 0"/>
+       </joint>
+
+       <joint name="imu_joint" type="fixed">
+               <parent link="mounting_plate"/>
+               <child link="base_imu_link"/>
+               <origin xyz="0.06 -0.03 0.058" rpy="0 0 0"/>
+       </joint>
+
+       <joint name="sonar_forward_joint" type="fixed">
+               <parent link="mounting_plate"/>
                <child link="sonar_forward"/>
                <origin xyz="0.115 0.0 -0.012" rpy="0 0 0"/>
        </joint>
 
        <joint name="sonar_backward_joint" type="fixed">
-               <parent link="base_link"/>
+               <parent link="mounting_plate"/>
                <child link="sonar_backward"/>
                <origin xyz="-0.115 0.0 -0.012" rpy="0 ${PI} 0"/>
        </joint>
 
        <joint name="ir_left_joint" type="fixed">
-               <parent link="base_link"/>
+               <parent link="mounting_plate"/>
                <child link="ir_left"/>
                <origin xyz="0.0 ${0.072+0.015} -0.045" rpy="0 0 ${PI/2}"/>
        </joint>
 
        <joint name="ir_right_joint" type="fixed">
-               <parent link="base_link"/>
+               <parent link="mounting_plate"/>
                <child link="ir_right"/>
                <origin xyz="0.0 ${-0.072-0.015} -0.045" rpy="0 0 ${-PI/2}"/>
        </joint>
+
+       <xacro:macro name="wheel" params="pos side xyz rpy">   
+               <link name="${pos}_${side}_wheel">
+                       <visual>
+                               <origin xyz="0 0 0" rpy="0 0 0"/>
+                               <geometry>
+                                       <mesh filename="package://wild_thumper/meshes/wheel_${side}.stl" />
+                               </geometry>
+                       </visual>
+                       <collision>
+                               <origin xyz="0 0 0" rpy="${-PI/2} 0 0"/>
+                               <geometry>
+                                       <cylinder radius="0.06" length="0.06"/>
+                               </geometry>
+                       </collision>
+                       <inertial>
+                               <origin xyz="0 0 0" rpy="0 0 0"/>
+                               <mass value="0.1"/>
+                               <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
+                       </inertial>
+               </link>
+               <joint name="${pos}_${side}_wheel_joint" type="continuous">
+                       <parent link="base_link"/>
+                       <child link="${pos}_${side}_wheel"/>
+                       <axis xyz="0 1 0"/>
+                       <origin xyz="${xyz}" rpy="${rpy}"/>
+               </joint>
+       </xacro:macro>
+
+       <gazebo reference="front_left_wheel">
+               <dampingFactor>0.001</dampingFactor>
+       </gazebo>
+       <gazebo reference="front_right_wheel">
+               <dampingFactor>0.001</dampingFactor>
+       </gazebo>
+
+       <xacro:wheel pos="aft" side="left"  xyz="-0.06398 0.11407 -0.022446" rpy="0 0 0" />
+       <xacro:wheel pos="aft" side="right" xyz="-0.07397 -0.11408 -0.022446" rpy="0 0 0" />
+       <xacro:wheel pos="front" side="left"  xyz="0.07602 0.11407 -0.022446" rpy="0 0 0" />
+       <xacro:wheel pos="front" side="right" xyz="0.07397 -0.11408 -0.022446" rpy="0 0 0" />
+
+       <gazebo>
+               <plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
+                       <robotNamespace>/</robotNamespace>
+                       <jointName>aft_left_wheel_joint, aft_right_wheel_joint, front_left_wheel_joint, front_right_wheel_joint</jointName>
+                       <updateRate>10.0</updateRate>
+                       <alwaysOn>true</alwaysOn>
+               </plugin>
+
+               <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
+                       <robotNamespace>/</robotNamespace>
+                       <alwaysOn>true</alwaysOn>
+                       <updateRate>10.0</updateRate>
+                       <leftJoint>aft_right_wheel_joint</leftJoint>
+                       <rightJoint>aft_left_wheel_joint</rightJoint>
+                       <wheelSeparation>0.252</wheelSeparation>
+                       <wheelDiameter>0.12</wheelDiameter>
+                       <wheelTorque>5.0</wheelTorque>
+                       <commandTopic>cmd_vel</commandTopic>
+                       <odometryTopic>odom</odometryTopic>
+                       <odometryFrame>odom</odometryFrame>
+                       <robotBaseFrame>base_footprint</robotBaseFrame>
+                       <rosDebugLevel>Info</rosDebugLevel>
+                       <publishWheelTF>false</publishWheelTF>
+                       <publishWheelJointState>true</publishWheelJointState>
+                       <wheelAcceleration>0.0</wheelAcceleration>
+                       <odometrySource>world</odometrySource>
+                       <publishTf>true</publishTf>
+               </plugin>
+       </gazebo>
 </robot>
diff --git a/worlds/test.world b/worlds/test.world
new file mode 100644 (file)
index 0000000..8fc420c
--- /dev/null
@@ -0,0 +1,16 @@
+<?xml version="1.0" ?>
+<sdf version="1.4" >
+       <world name="default" >
+               <include>
+                       <uri>model://ground_plane</uri>
+               </include>
+               <include>
+                       <uri>model://sun</uri>
+               </include>
+               <include>
+                       <uri>model://gas_station</uri>
+                       <name>gas_station</name>
+                       <pose>-2.0 7.0 0 0 0 0</pose>
+               </include>
+       </world>
+</sdf>