Skip to content
This repository was archived by the owner on Feb 21, 2021. It is now read-only.
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions src/drivers/gazeboserver/gazebo-setup.sh
Original file line number Diff line number Diff line change
Expand Up @@ -6,5 +6,5 @@
# JdeRobot resources
export GAZEBO_RESOURCE_PATH=$GAZEBO_RESOURCE_PATH:/usr/local/share/jderobot/gazebo/models:/usr/local/share/jderobot/gazebo/worlds
export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:/usr/local/share/jderobot/gazebo/models
export GAZEBO_PLUGIN_PATH=$GAZEBO_PLUGIN_PATH:/usr/local/share/jderobot/gazebo/plugins/pioneer:/usr/local/share/jderobot/gazebo/plugins/nao:/usr/local/share/jderobot/gazebo/plugins/kinect:/usr/local/share/jderobot/gazebo/plugins/quadrotor:/usr/local/share/jderobot/gazebo/plugins/turtlebot:/usr/local/share/jderobot/gazebo/plugins/flyingkinect:/usr/local/share/jderobot/gazebo/plugins/car:/usr/local/share/jderobot/gazebo/plugins/f1
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/usr/local/lib/jderobot:/usr/local/share/jderobot/gazebo/plugins/pioneer:/usr/local/share/jderobot/gazebo/plugins/nao:/usr/local/share/jderobot/gazebo/plugins/kinect:/usr/local/share/jderobot/gazebo/plugins/quadrotor:/usr/local/share/jderobot/gazebo/plugins/turtlebot:/usr/local/share/jderobot/gazebo/plugins/flyingkinect:/usr/local/share/jderobot/gazebo/plugins/car:/usr/local/share/jderobot/gazebo/plugins/f1
export GAZEBO_PLUGIN_PATH=$GAZEBO_PLUGIN_PATH:/usr/local/share/jderobot/gazebo/plugins/pioneer:/usr/local/share/jderobot/gazebo/plugins/nao:/usr/local/share/jderobot/gazebo/plugins/kinect:/usr/local/share/jderobot/gazebo/plugins/quadrotor:/usr/local/share/jderobot/gazebo/plugins/turtlebot:/usr/local/share/jderobot/gazebo/plugins/flyingkinect:/usr/local/share/jderobot/gazebo/plugins/car:/usr/local/share/jderobot/gazebo/plugins/f1:/usr/local/share/jderobot/gazebo/plugins/roomba
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/usr/local/lib/jderobot:/usr/local/share/jderobot/gazebo/plugins/pioneer:/usr/local/share/jderobot/gazebo/plugins/nao:/usr/local/share/jderobot/gazebo/plugins/kinect:/usr/local/share/jderobot/gazebo/plugins/quadrotor:/usr/local/share/jderobot/gazebo/plugins/turtlebot:/usr/local/share/jderobot/gazebo/plugins/flyingkinect:/usr/local/share/jderobot/gazebo/plugins/car:/usr/local/share/jderobot/gazebo/plugins/f1:/usr/local/share/jderobot/gazebo/plugins/roomba
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
348 changes: 348 additions & 0 deletions src/drivers/gazeboserver/models/roomba/meshes/create_body.dae

Large diffs are not rendered by default.

235 changes: 235 additions & 0 deletions src/drivers/gazeboserver/models/roomba/meshes/hokuyo.dae

Large diffs are not rendered by default.

19 changes: 19 additions & 0 deletions src/drivers/gazeboserver/models/roomba/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?xml version="1.0"?>

<model>
<name>iRobot Roomba</name>
<version>1.0</version>
<sdf version="1.5">model.sdf</sdf>

<author>
<name>Nate Koenig</name>
<email>nate@osrfoundation.org</email>
</author>

<description>
A model of the iRobot Create.
</description>

<depend>
</depend>
</model>
371 changes: 371 additions & 0 deletions src/drivers/gazeboserver/models/roomba/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,371 @@
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="roomba">

<plugin name='roombaplugin' filename='libroombaplugin.so'>
<alwaysOn>1</alwaysOn>
<updateRate>10.0</updateRate>
<bodyName>base</bodyName>
<left_joint>left_wheel</left_joint>
<right_joint>right_wheel</right_joint>
<!-- Ice configuration -->
<iceConfigFile>roombaplugin.cfg</iceConfigFile>
<!--iceAdapterPort>9000</iceAdapterPort-->
</plugin>
<link name="base">
<inertial>
<pose>0.001453 -0.000453 0.029787 0 0 0</pose>
<inertia>
<ixx>0.058640</ixx>
<ixy>0.000124</ixy>
<ixz>0.000615</ixz>
<iyy>0.058786</iyy>
<iyz>0.000014</iyz>
<izz>1.532440</izz>
</inertia>
<mass>2.234000</mass>
</inertial>
<collision name="base_collision">
<pose>0 0 0.047800 0 0 0</pose>
<geometry>
<mesh>
<uri>model://roomba/meshes/create_body.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="base_visual">
<pose>0 0 0.047800 0 0 0</pose>
<geometry>
<mesh>
<uri>model://roomba/meshes/create_body.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="front_wheel_collision">
<pose>0.130000 0 0.017000 0 1.570700 1.570700</pose>
<geometry>
<sphere>
<radius>0.018000</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="front_wheel_visual">
<pose>0.130000 0 0.017000 0 1.570700 1.570700</pose>
<geometry>
<sphere>
<radius>0.009000</radius>
</sphere>
</geometry>
</visual>
<collision name="rear_wheel_collision">
<pose>-0.13 0 0.017 0 1.5707 1.5707</pose>
<geometry>
<sphere>
<radius>0.015000</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="rear_wheel_visual">
<pose>-0.130000 0 0.017000 0 1.570700 1.570700</pose>
<geometry>
<sphere>
<radius>0.007500</radius>
</sphere>
</geometry>
</visual>
<sensor name="bumper" type='contact'>
<contact>
<collision>base_collision</collision>
</contact>
</sensor>
<sensor name="left_cliff_sensor" type="ray">
<pose>0.070000 0.140000 0.027000 0 1.570790 0</pose>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1.000000</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.010000</min>
<max>0.040000</max>
<resolution>0.100000</resolution>
</range>
</ray>
</sensor>
<sensor name="leftfront_cliff_sensor" type="ray">
<pose>0.150000 0.040000 0.027000 0 1.570790 0</pose>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1.000000</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.010000</min>
<max>0.040000</max>
<resolution>0.100000</resolution>
</range>
</ray>
</sensor>
<sensor name="right_cliff_sensor" type="ray">
<pose>0.070000 -0.140000 0.027000 0 1.570790 0</pose>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1.000000</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.010000</min>
<max>0.040000</max>
<resolution>0.100000</resolution>
</range>
</ray>
</sensor>
<sensor name="rightfront_cliff_sensor" type="ray">
<pose>0.150000 -0.040000 0.027000 0 1.570790 0</pose>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1.000000</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.010000</min>
<max>0.040000</max>
<resolution>0.100000</resolution>
</range>
</ray>
</sensor>
<sensor name="wall_sensor" type="ray">
<pose>0.090000 -0.120000 0.059000 0 0 -1.000000</pose>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1.000000</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.016000</min>
<max>0.040000</max>
<resolution>0.100000</resolution>
</range>
</ray>
</sensor>
</link>
<link name="left_wheel">
<pose>0 0.130000 0.032000 0 0 0</pose>
<inertial>
<inertia>
<ixx>0.001000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.001000</iyy>
<iyz>0</iyz>
<izz>0.001000</izz>
</inertia>
<mass>0.010000</mass>
</inertial>
<collision name="collision">
<pose>0 0 0 0 1.570700 1.570700</pose>
<geometry>
<cylinder>
<radius>0.033000</radius>
<length>0.023000</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>10</mu>
<mu2>10</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<pose>0 0 0 0 1.570700 1.570700</pose>
<geometry>
<cylinder>
<radius>0.033000</radius>
<length>0.023000</length>
</cylinder>
</geometry>
</visual>
</link>
<link name="right_wheel">
<pose>0 -0.130000 0.032000 0 0 0</pose>
<inertial>
<inertia>
<ixx>0.001000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.001000</iyy>
<iyz>0</iyz>
<izz>0.001000</izz>
</inertia>
<mass>0.010000</mass>
</inertial>
<collision name="collision">
<pose>0 0 0 0 1.570700 1.570700</pose>
<geometry>
<cylinder>
<radius>0.033000</radius>
<length>0.023000</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>10</mu>
<mu2>10</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<pose>0 0 0 0 1.570700 1.570700</pose>
<geometry>
<cylinder>
<radius>0.033000</radius>
<length>0.023000</length>
</cylinder>
</geometry>
</visual>
</link>
<link name='laser'>
<pose>0.139000 0.000000 0.0752000 0.000000 0.000000 0.000000</pose>
<gravity>0</gravity>
<inertial>
<mass>0.100000</mass>
<inertia>
<ixx>1.000000</ixx>
<ixy>0.000000</ixy>
<ixz>0.000000</ixz>
<iyy>1.000000</iyy>
<iyz>0.000000</iyz>
<izz>1.000000</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<mesh>
<uri>model://roomba/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<collision name='collision-base'>
<pose>0.000000 0.000000 -0.014500 0.000000 0.000000 0.000000</pose>
<geometry>
<box>
<size>0.050000 0.050000 0.041000</size>
</box>
</geometry>
<max_contacts>10</max_contacts>
</collision>
<collision name='collision-top'>
<pose>0.000000 0.000000 0.020500 0.000000 0.000000 0.000000</pose>
<geometry>
<cylinder>
<radius>0.021000</radius>
<length>0.029000</length>
</cylinder>
</geometry>
<max_contacts>10</max_contacts>
</collision>
<sensor name='laser' type='ray'>
<ray>
<scan>
<horizontal>
<samples>180</samples>
<resolution>1.000000</resolution>
<min_angle>-1.570000</min_angle>
<max_angle>1.570000</max_angle>
</horizontal>
</scan>
<range>
<min>0.080000</min>
<max>10.000000</max>
<resolution>0.010000</resolution>
</range>
</ray>
<update_rate>20.000000</update_rate>
<always_on>1</always_on>
<visualize>1</visualize>
</sensor>
<velocity_decay>
<linear>0.000000</linear>
<angular>0.000000</angular>
</velocity_decay>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<joint name="left_wheel" type="revolute">
<parent>base</parent>
<child>left_wheel</child>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>true</use_parent_model_frame>
</axis>
</joint>
<joint name="right_wheel" type="revolute">
<parent>base</parent>
<child>right_wheel</child>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>true</use_parent_model_frame>
</axis>
</joint>
<joint name='joint_laser' type='fixed'>
<parent>base</parent>
<child>laser</child>
<axis>
<xyz>0 0 0</xyz>
</axis>
</joint>
</model>
</sdf>
Loading