Skip to content

Commit

Permalink
Merge pull request #13 from robotology/addLaser2
Browse files Browse the repository at this point in the history
Double laser for CER-SIM
  • Loading branch information
randaz81 authored Aug 26, 2019
2 parents 93a3887 + 09342c3 commit 0a4f076
Show file tree
Hide file tree
Showing 6 changed files with 7,901 additions and 14 deletions.
46 changes: 40 additions & 6 deletions gazebo/cer/cer.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://cer/meshes/dae/sim_cer_mobilebase_body.dae</uri>
<uri>model://cer/meshes/obj/sim_cer_mobilebase_body.obj</uri>
</mesh>
</geometry>
<surface>
Expand All @@ -40,7 +40,7 @@
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://cer/meshes/dae/sim_cer_mobilebase_body.dae</uri>
<uri>model://cer/meshes/obj/sim_cer_mobilebase_body.obj</uri>
</mesh>
</geometry>
<material>
Expand All @@ -55,17 +55,18 @@
<always_on>1</always_on>
<update_rate>40</update_rate>
<pose frame=''>0.07 0 0.031 0 -0 0</pose>
<visualize>true</visualize>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>-3.14</min_angle>
<max_angle>3.14</max_angle>
<resolution>2</resolution>
<min_angle>0</min_angle>
<max_angle>6.28</max_angle>
</horizontal>
</scan>
<range>
<min>0.1</min>
<min>0.04</min>
<max>5</max>
<resolution>0.01</resolution>
</range>
Expand All @@ -79,6 +80,36 @@
<yarpConfigurationFile>model://cer/conf/gazebo_cer_laser_sensor.ini</yarpConfigurationFile>
</plugin>
</sensor>
<sensor name='base_laser2' type='ray'>
<always_on>1</always_on>
<update_rate>40</update_rate>
<pose frame=''>-0.085 0 0.031 0 0 3.14159</pose>
<visualize>true</visualize>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>2</resolution>
<min_angle>0</min_angle>
<max_angle>6.28</max_angle>
</horizontal>
</scan>
<range>
<min>0.04</min>
<max>5</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.005</stddev>
</noise>
</ray>
<plugin name='laser_sensor2' filename='libgazebo_yarp_lasersensor.so'>
<yarpConfigurationFile>model://cer/conf/gazebo_cer_laser_sensor2.ini</yarpConfigurationFile>
</plugin>
</sensor>

<gravity>1</gravity>
<velocity_decay/>
</link>
Expand Down Expand Up @@ -2292,6 +2323,9 @@
<plugin name='world_interface' filename='libgazebo_yarp_worldinterface.so'>
<yarpConfigurationFile>model://cer/conf/worldInterface.ini</yarpConfigurationFile>
</plugin>
<plugin name='double_laser' filename='libgazebo_yarp_doublelaser.so'>
<yarpConfigurationFile>model://cer/conf/gazebo_cer_doublelaser.ini</yarpConfigurationFile>
</plugin>
<static>0</static>
<pose frame=''>0 0 0.16 0 -0 0</pose>
</model>
Expand Down
27 changes: 27 additions & 0 deletions gazebo/cer/conf/gazebo_cer_doublelaser.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
[include "gazebo_cer_robotname.ini"]

robotName ${gazeboYarpPluginsRobotName}

onSimulator true

[WRAPPER]
device Rangefinder2DWrapper
period 10
name /${gazeboYarpPluginsRobotName}/laser:o

[ROS]
useROS true
ROS_nodeName /${gazeboYarpPluginsRobotName}-laser
ROS_topicName /laser
frame_id /mobile_base_double_lidar

[LASERFRONT-CFG]
sensorName base_laser
pose 0.070 0.0 0.031 0
file gazebo_cer_laser_sensor.ini

[LASERBACK-CFG]
sensorName base_laser2
pose -0.085 0.0 0.031 3.14159
file gazebo_cer_laser_sensor2.ini

16 changes: 8 additions & 8 deletions gazebo/cer/conf/gazebo_cer_laser_sensor.ini
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,13 @@ deviceId base_laser
period 10

device gazebo_lasersensor
name /${gazeboYarpPluginsRobotName}/laser
name /${gazeboYarpPluginsRobotName}/laser/front:o

[ROS]
useROS true
ROS_nodeName /cer_laser
ROS_topicName /laser
frame_id /mobile_base_body_link
ROS_nodeName /${gazeboYarpPluginsRobotName}-laserFront
ROS_topicName /laserFront
frame_id /mobile_base_lidar_F

[GENERAL]
enable_clip_range 0
Expand All @@ -20,11 +20,11 @@ clip_min_range 0.2
enable_discard_range 1
discard_max_range 5.0
discard_min_range 0.2
max_angle 359
max_angle 360
min_angle 0
resolution 1
resolution 0.5
allow_infinity 1

[SKIP]
min 0 240
max 120 360
min 35
max 325
30 changes: 30 additions & 0 deletions gazebo/cer/conf/gazebo_cer_laser_sensor2.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
[include "gazebo_cer_robotname.ini"]

robotName ${gazeboYarpPluginsRobotName}
deviceId base_laser2
period 10

device gazebo_lasersensor
name /${gazeboYarpPluginsRobotName}/laser/back:o

[ROS]
useROS true
ROS_nodeName /${gazeboYarpPluginsRobotName}-laserBack
ROS_topicName /laserBack
frame_id /mobile_base_lidar_B

[GENERAL]
enable_clip_range 0
clip_max_range 5.0
clip_min_range 0.2
enable_discard_range 1
discard_max_range 5.0
discard_min_range 0.2
max_angle 360
min_angle 0
resolution 0.5
allow_infinity 1

[SKIP]
min 60
max 300
6 changes: 6 additions & 0 deletions gazebo/cer/meshes/obj/sim_cer_mobilebase_body.mtl
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
newmtl DEFAULT_MTL
Kd 0.635 0.686 0.749

newmtl MTL0
Kd 0.071 0.075 0.078

Loading

0 comments on commit 0a4f076

Please sign in to comment.