Skip to content

Commit

Permalink
Demo worlds, doxygen, more node tests
Browse files Browse the repository at this point in the history
  • Loading branch information
chapulina committed Oct 24, 2018
1 parent 0d30879 commit 8e16591
Show file tree
Hide file tree
Showing 8 changed files with 670 additions and 1 deletion.
29 changes: 29 additions & 0 deletions gazebo_plugins/include/gazebo_plugins/gazebo_ros_camera.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,35 @@ namespace gazebo_plugins
class GazeboRosCameraPrivate;

/// A plugin that publishes raw images and camera info for generic camera sensors.
/**
Example Usage:
\code{.xml}
<plugin name="plugin_name" filename="libgazebo_ros_camera.so">
<!-- Change namespace, camera name and topics so:
* Images are published to: /custom_ns/custom_camera/custom_image
* Camera info is published to: /custom_ns/custom_camera/custom_info
* Trigger is received on: /custom_ns/custom_camera/custom_trigger
-->
<ros>
<namespace>custom_ns</namespace>
<argument>image_raw:=custom_img</argument>
<argument>camera_info:=custom_info</argument>
<argument>image_trigger:=custom_trigger</argument>
</ros>
<!-- Set camera name. If empty, defaults to sensor name -->
<camera_name>custom_camera</camera_name>
<!-- Set TF frame name. If empty, defaults to link name -->
<frame_name>custom_frame</frame_name>
<!-- Set to true to turn on triggering -->
<triggered>true</triggered>
<hack_baseline>0.07</hack_baseline>
</plugin>
\endcode
*/
class GazeboRosCamera : public gazebo::CameraPlugin
{
public:
Expand Down
2 changes: 1 addition & 1 deletion gazebo_plugins/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ endforeach()
# Tests
set(tests
test_gazebo_ros_camera
# TODO(louise) Test passes but crashes on teardown, bt points to ~GLRenderBuffer
# TODO(louise) Test hangs on teardown while destroying 2nd node
# test_gazebo_ros_camera_distortion
test_gazebo_ros_camera_triggered
test_gazebo_ros_diff_drive
Expand Down
1 change: 1 addition & 0 deletions gazebo_plugins/test/test_gazebo_ros_camera_distortion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ class GazeboRosCameraDistortionTest
cam_sub_undistorted_.shutdown();
cam_sub_distorted_.shutdown();
cam_info_distorted_sub_.reset();
ServerFixture::TearDown();
}

/// Subscribe to distorted images.
Expand Down
151 changes: 151 additions & 0 deletions gazebo_plugins/worlds/gazebo_ros_camera_demo.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,151 @@
<?xml version="1.0" ?>
<!--
Gazebo ROS camera plugin demo
Try for example:
* Launch RViz and visualize Images from `/demo_cam/camera1/image_raw/raw`
-->
<sdf version="1.6">
<world name="default">

<include>
<uri>model://sun</uri>
</include>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
</ode>
</friction>
<bounce>
<restitution_coefficient>1.0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<max_vel>10000</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="visual">
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
</model>

<model name="ball">
<allow_auto_disable>false</allow_auto_disable>
<pose>-1 0 1 0 0 0</pose>
<static>false</static>
<link name="link">
<inertial>
<mass>0.026</mass>
<!-- inertia based on solid sphere 2/5 mr^2 -->
<inertia>
<ixx>1.664e-5</ixx>
<iyy>1.664e-5</iyy>
<izz>1.664e-5</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<sphere>
<radius>0.04</radius>
</sphere>
</geometry>
<surface>
<bounce>
<restitution_coefficient>1.0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<max_vel>10000</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="visual">
<geometry>
<sphere>
<radius>0.04</radius>
</sphere>
</geometry>
</visual>
</link>
</model>

<model name="camera_model">
<pose>0 0 0.5 0 0 3.14</pose>
<static>true</static>
<link name="camera_link">
<sensor type="camera" name="camera1">
<update_rate>60</update_rate>
<visualize>true</visualize>
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<ros>
<namespace>demo_cam</namespace>
<!-- TODO(louise) Remapping not working due to https://github.com/ros-perception/image_common/issues/93 -->
<argument>image_raw:=image_demo</argument>
<argument>camera_info:=camera_info_demo</argument>
</ros>
<!-- camera_name>omit so it defaults to sensor name</camera_name-->
<!-- frame_name>omit so it defaults to link name</frameName-->
</plugin>
</sensor>
</link>
</model>
</world>
</sdf>
149 changes: 149 additions & 0 deletions gazebo_plugins/worlds/gazebo_ros_camera_distortion_barrel_demo.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,149 @@
<?xml version="1.0" ?>
<!--
Gazebo ROS camera with barrel distortion plugin demo
Try for example:
* Launch RViz and visualize Images from `/camera1/image_raw/raw`
-->
<sdf version="1.6">
<world name="default">

<include>
<uri>model://sun</uri>
</include>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
</ode>
</friction>
<bounce>
<restitution_coefficient>1.0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<max_vel>10000</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="visual">
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
</model>

<model name="ball">
<allow_auto_disable>false</allow_auto_disable>
<pose>-1 0 1 0 0 0</pose>
<static>false</static>
<link name="link">
<inertial>
<mass>0.026</mass>
<!-- inertia based on solid sphere 2/5 mr^2 -->
<inertia>
<ixx>1.664e-5</ixx>
<iyy>1.664e-5</iyy>
<izz>1.664e-5</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<sphere>
<radius>0.04</radius>
</sphere>
</geometry>
<surface>
<bounce>
<restitution_coefficient>1.0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<max_vel>10000</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="visual">
<geometry>
<sphere>
<radius>0.04</radius>
</sphere>
</geometry>
</visual>
</link>
</model>

<model name="camera_barrel">
<pose>0 0 0.5 0 0 3.14</pose>
<static>true</static>
<link name="barrel">
<sensor type="camera" name="camera_barrel">
<update_rate>60</update_rate>
<visualize>true</visualize>
<camera name="head">
<horizontal_fov>0.927295218</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<distortion>
<k1>-0.1</k1>
<k2>-0.1</k2>
<p1>0</p1>
<p2>0</p2>
<k3>-0.1</k3>
<center>0.5 0.5</center>
</distortion>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<border_crop>false</border_crop>
</plugin>
</sensor>
</link>
</model>

<include>
<pose>-1.5 0 1 0 1.57 0</pose>
<uri>model://checkerboard_plane</uri>
</include>
</world>
</sdf>
Loading

0 comments on commit 8e16591

Please sign in to comment.