|
From: <hsu...@us...> - 2008-12-24 17:55:15
|
Revision: 8571
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=8571&view=rev
Author: hsujohnhsu
Date: 2008-12-24 17:55:10 +0000 (Wed, 24 Dec 2008)
Log Message:
-----------
renamed gazebo_plugin files to somewhat ros standards. this affects plugin library names, so robot description <map> tags and some world files are updated as well.
Modified Paths:
--------------
pkg/trunk/demos/2dnav_gazebo/test/test_2dnav_empty.xml
pkg/trunk/demos/2dnav_gazebo/test/test_2dnav_wg.xml
pkg/trunk/demos/examples_gazebo/dual_link_defs/dual_link.xml
pkg/trunk/demos/examples_gazebo/multi_link_defs/multi_link.xml
pkg/trunk/demos/examples_gazebo/single_link_defs/single_link.xml
pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch
pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_empty.launch
pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_objects/object1.model
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_objects/object_small_box.model
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/obstacle.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tablegrasp.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tables.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_camera.world
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm.xacro.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_grav_arm.xacro.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_gripper/pr2_gripper.xacro.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/arm_defs.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/arm_grav_defs.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/base_defs.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/body_defs.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/gazebo_defs.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/gripper_defs.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/head_defs.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/ptz_defs.xml
Added Paths:
-----------
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_block_laser.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_bumper.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_camera.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_f3d.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_joint_force.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_laser.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_p3d.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_ptz.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_stereo_camera.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_time.h
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_block_laser.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_bumper.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_camera.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_f3d.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_joint_force.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_p3d.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_ptz.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_stereo_camera.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_time.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2factory.cpp
Removed Paths:
-------------
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/F3D.hh
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/P3D.hh
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Block_Laser.hh
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Bumper.hh
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Camera.hh
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_JointForce.hh
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Laser.hh
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_PTZ.hh
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Stereo_Camera.hh
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Time.hh
pkg/trunk/drivers/simulator/gazebo_plugin/src/F3D.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/P3D.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Bumper.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Camera.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_JointForce.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Laser.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Stereo_Camera.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Time.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2factory.cc
Modified: pkg/trunk/demos/2dnav_gazebo/test/test_2dnav_empty.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/test/test_2dnav_empty.xml 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/demos/2dnav_gazebo/test/test_2dnav_empty.xml 2008-12-24 17:55:10 UTC (rev 8571)
@@ -35,15 +35,15 @@
<test test-name="2dnav_gazebo_test_2dnav_empty_ympi" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 25.65 -y 23.51 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 50 " time-limit="60" />
<test test-name="2dnav_gazebo_test_2dnav_empty_ym1" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 25.65 -y 24.65 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 50 " time-limit="60" />
- <test test-name="2dnav_gazebo_test_2dnav_empty_y1" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 25.65 -y 26.65 -t 0 -nav_tol 0.70 -odom_tol 0.06 -timeout 50 " time-limit="60" />
- <test test-name="2dnav_gazebo_test_2dnav_empty_ypi" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 25.65 -y 28.79 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 50 " time-limit="60" />
+ <test test-name="2dnav_gazebo_test_2dnav_empty_y1" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 25.65 -y 26.65 -t 0 -nav_tol 0.70 -odom_tol 0.06 -timeout 80 " time-limit="90" />
+ <test test-name="2dnav_gazebo_test_2dnav_empty_ypi" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 25.65 -y 28.79 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 80 " time-limit="90" />
<test test-name="2dnav_gazebo_test_2dnav_empty_x1y1" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 26.65 -y 26.65 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 50 " time-limit="60" />
<test test-name="2dnav_gazebo_test_2dnav_empty_xm1y1" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 24.65 -y 26.65 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 50 " time-limit="60" />
<test test-name="2dnav_gazebo_test_2dnav_empty_x1ym1" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 26.65 -y 24.65 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 50 " time-limit="60" />
<test test-name="2dnav_gazebo_test_2dnav_empty_xm1ym1" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 24.65 -y 24.65 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 50 " time-limit="60" />
- <test test-name="2dnav_gazebo_test_2dnav_empty_xpiypi" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 28.79 -y 28.79 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 80 " time-limit="90" />
+ <test test-name="2dnav_gazebo_test_2dnav_empty_xpiypi" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 28.79 -y 28.79 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 110 " time-limit="120" />
<test test-name="2dnav_gazebo_test_2dnav_empty_xmpiypi" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 23.51 -y 28.79 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 80 " time-limit="90" />
<test test-name="2dnav_gazebo_test_2dnav_empty_xpiympi" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 28.79 -y 23.51 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 80 " time-limit="90" />
<test test-name="2dnav_gazebo_test_2dnav_empty_xmpiympi" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 23.51 -y 23.51 -t 0 -nav_tol 0.70 -odom_tol 0.05 -timeout 80 " time-limit="90" />
Modified: pkg/trunk/demos/2dnav_gazebo/test/test_2dnav_wg.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/test/test_2dnav_wg.xml 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/demos/2dnav_gazebo/test/test_2dnav_wg.xml 2008-12-24 17:55:10 UTC (rev 8571)
@@ -28,12 +28,12 @@
-->
<!-- test -->
- <test test-name="2dnav_gazebo_test_2dnav_wg_1" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 40.8 -y 42.5 -t 3.083 -nav_tol 0.70 -odom_tol 0.05 -timeout 110 " time-limit="120"/>
- <test test-name="2dnav_gazebo_test_2dnav_wg_2" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 36.0 -y 34.9 -t 2.554 -nav_tol 0.70 -odom_tol 0.03 -timeout 110 " time-limit="120"/>
- <test test-name="2dnav_gazebo_test_2dnav_wg_3" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 31.3 -y 45.8 -t 0.000 -nav_tol 0.70 -odom_tol 0.01 -timeout 110 " time-limit="120"/>
- <test test-name="2dnav_gazebo_test_2dnav_wg_4" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 22.2 -y 20.0 -t 0.000 -nav_tol 0.70 -odom_tol 0.01 -timeout 110 " time-limit="120"/>
- <test test-name="2dnav_gazebo_test_2dnav_wg_5" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 7.5 -y 45.0 -t 1.571 -nav_tol 0.70 -odom_tol 0.05 -timeout 110 " time-limit="120"/>
- <test test-name="2dnav_gazebo_test_2dnav_wg_6" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 9.4 -y 11.2 -t 0.000 -nav_tol 0.70 -odom_tol 0.05 -timeout 110 " time-limit="120"/>
+ <test test-name="2dnav_gazebo_test_2dnav_wg_1" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 40.8 -y 42.5 -t 3.083 -nav_tol 0.70 -odom_tol 0.05 -timeout 290 " time-limit="300"/>
+ <test test-name="2dnav_gazebo_test_2dnav_wg_2" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 36.0 -y 34.9 -t 2.554 -nav_tol 0.70 -odom_tol 0.03 -timeout 290 " time-limit="300"/>
+ <test test-name="2dnav_gazebo_test_2dnav_wg_3" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 31.3 -y 45.8 -t 0.000 -nav_tol 0.70 -odom_tol 0.01 -timeout 290 " time-limit="300"/>
+ <test test-name="2dnav_gazebo_test_2dnav_wg_4" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 22.2 -y 20.0 -t 0.000 -nav_tol 0.70 -odom_tol 0.01 -timeout 290 " time-limit="300"/>
+ <test test-name="2dnav_gazebo_test_2dnav_wg_5" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 7.5 -y 45.0 -t 1.571 -nav_tol 0.70 -odom_tol 0.05 -timeout 290 " time-limit="300"/>
+ <test test-name="2dnav_gazebo_test_2dnav_wg_6" pkg="2dnav_gazebo" type="test_2dnav_translations.py" args=" -x 9.4 -y 11.2 -t 0.000 -nav_tol 0.70 -odom_tol 0.05 -timeout 290 " time-limit="300"/>
<!--
-->
</launch>
Modified: pkg/trunk/demos/examples_gazebo/dual_link_defs/dual_link.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/dual_link_defs/dual_link.xml 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/demos/examples_gazebo/dual_link_defs/dual_link.xml 2008-12-24 17:55:10 UTC (rev 8571)
@@ -128,7 +128,7 @@
<map name="sensor" flag="gazebo">
<verbatim key="mechanism_control_simulation">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
+ <controller:ros_time name="ros_time" plugin="libros_time.so">
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
@@ -142,8 +142,8 @@
<interface:audio name="gazebo_mechanism_control_dummy_iface" />
</controller:gazebo_mechanism_control>
- <!-- P3D for position groundtruth -->
- <controller:P3D name="p3d_link1_controller" plugin="libP3D.so">
+ <!-- ros_p3d for position groundtruth -->
+ <controller:ros_p3d name="p3d_link1_controller" plugin="libros_p3d.so">
<alwaysOn>true</alwaysOn>
<updateRate>1000.0</updateRate>
<bodyName>link1</bodyName>
@@ -152,17 +152,17 @@
<xyzOffsets>0 0 0.0</xyzOffsets>
<rpyOffsets>0 0 0.0</rpyOffsets>
<interface:position name="p3d_link1_position"/>
- </controller:P3D>
+ </controller:ros_p3d>
- <!-- P3D for position groundtruth -->
- <controller:P3D name="p3d_link2_controller" plugin="libP3D.so">
+ <!-- ros_p3d for position groundtruth -->
+ <controller:ros_p3d name="p3d_link2_controller" plugin="libros_p3d.so">
<alwaysOn>true</alwaysOn>
<updateRate>1000.0</updateRate>
<bodyName>link2</bodyName>
<topicName>link2_pose</topicName>
<frameName>map</frameName>
<interface:position name="p3d_link2_position"/>
- </controller:P3D>
+ </controller:ros_p3d>
</verbatim>
</map>
Modified: pkg/trunk/demos/examples_gazebo/multi_link_defs/multi_link.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/multi_link_defs/multi_link.xml 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/demos/examples_gazebo/multi_link_defs/multi_link.xml 2008-12-24 17:55:10 UTC (rev 8571)
@@ -343,7 +343,7 @@
<map name="sensor" flag="gazebo">
<verbatim key="mechanism_control_simulation">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
+ <controller:ros_time name="ros_time" plugin="libros_time.so">
<alwaysOn>true</alwaysOn>
<updateRate>1000.0</updateRate>
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
@@ -357,15 +357,15 @@
<interface:audio name="gazebo_mechanism_control_dummy_iface" />
</controller:gazebo_mechanism_control>
- <!-- P3D for position groundtruth -->
- <controller:P3D name="p3d_link3_controller" plugin="libP3D.so">
+ <!-- ros_p3d for position groundtruth -->
+ <controller:ros_p3d name="p3d_link3_controller" plugin="libros_p3d.so">
<alwaysOn>true</alwaysOn>
<updateRate>1000.0</updateRate>
<bodyName>link3</bodyName>
<topicName>link3_pose</topicName>
<frameName>map</frameName>
<interface:position name="p3d_link3_position"/>
- </controller:P3D>
+ </controller:ros_p3d>
</verbatim>
</map>
Modified: pkg/trunk/demos/examples_gazebo/single_link_defs/single_link.xml
===================================================================
--- pkg/trunk/demos/examples_gazebo/single_link_defs/single_link.xml 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/demos/examples_gazebo/single_link_defs/single_link.xml 2008-12-24 17:55:10 UTC (rev 8571)
@@ -82,7 +82,7 @@
<map name="sensor" flag="gazebo">
<verbatim key="mechanism_control_simulation">
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
+ <controller:ros_time name="ros_time" plugin="libros_time.so">
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
@@ -95,15 +95,15 @@
<interface:audio name="gazebo_mechanism_control_dummy_iface" />
</controller:gazebo_mechanism_control>
- <!-- P3D for position groundtruth -->
- <controller:P3D name="p3d_link1_controller" plugin="libP3D.so">
+ <!-- ros_p3d for position groundtruth -->
+ <controller:ros_p3d name="p3d_link1_controller" plugin="libros_p3d.so">
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<bodyName>link1</bodyName>
<topicName>link1_pose</topicName>
<frameName>map</frameName>
<interface:position name="p3d_link1_position"/>
- </controller:P3D>
+ </controller:ros_p3d>
</verbatim>
</map>
<!-- Define groups of links; a link may be part of multiple groups -->
Modified: pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch
===================================================================
--- pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch 2008-12-24 17:55:10 UTC (rev 8571)
@@ -18,5 +18,9 @@
<!--node pkg="pr2_mechanism_controllers" type="control_laser.py" args="laser_tilt_controller sine 1 .45 .40" /--> <!-- this one will pick up shoulders at lowest position -->
<node pkg="mechanism_control" type="spawner.py" args="$(find wg_robot_description)/laser_tilt/laser_tilt_controller.xml" />
<node pkg="pr2_mechanism_controllers" type="control_laser.py" args="laser_tilt_controller sine 2 .45 .40" />
+
+ <!-- send arm a command -->
+ <node pkg="robot_mechanism_controllers" type="control.py" args="set l_gripper_controller 0.05" respawn="false" output="screen" /> <!-- open gripper .5 radians -->
+ <node pkg="robot_mechanism_controllers" type="control.py" args="set r_gripper_controller 0.05" respawn="false" output="screen" /> <!-- open gripper .5 radians -->
</launch>
Modified: pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_empty.launch
===================================================================
--- pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_empty.launch 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_empty.launch 2008-12-24 17:55:10 UTC (rev 8571)
@@ -15,7 +15,7 @@
<env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
</node>
- <!-- push robotdesc/pr2 to factory and spawn robot in gazebo -->
+ <!-- push robotdesc/pr2 to factory and spawn robot in gazebo, the initial coordinates here is in Gazebo format, in the map frame, add offsets from P3D plugin (25.65,25.65) -->
<node pkg="gazebo_plugin" type="urdf2factory" args="robotdesc/pr2 0 0 0 0 0 0" respawn="false" output="screen" /> <!-- load default arm controller -->
<!-- use mech.py to spawn all controllers listed in controllers.xml -->
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt 2008-12-24 17:55:10 UTC (rev 8571)
@@ -9,22 +9,18 @@
add_definitions(-fPIC)
set(ROS_BUILD_TYPE Release)
-rospack_add_library(Ros_Stereo_Camera src/Ros_Stereo_Camera.cc)
-rospack_add_library(Ros_Camera src/Ros_Camera.cc)
-rospack_add_library(Ros_Laser src/Ros_Laser.cc)
-rospack_add_library(Ros_Block_Laser src/Ros_Block_Laser.cc)
-rospack_add_library(Ros_Time src/Ros_Time.cc)
-rospack_add_library(Ros_PTZ src/Ros_PTZ.cc)
-rospack_add_library(P3D src/P3D.cc)
-rospack_add_library(F3D src/F3D.cc)
+rospack_add_library(ros_stereo_camera src/ros_stereo_camera.cpp)
+rospack_add_library(ros_camera src/ros_camera.cpp)
+rospack_add_library(ros_laser src/ros_laser.cpp)
+rospack_add_library(ros_block_laser src/ros_block_laser.cpp)
+rospack_add_library(ros_time src/ros_time.cpp)
+rospack_add_library(ros_ptz src/ros_ptz.cpp)
+rospack_add_library(ros_p3d src/ros_p3d.cpp)
+rospack_add_library(ros_f3d src/ros_f3d.cpp)
rospack_add_library(gazebo_mechanism_control src/gazebo_mechanism_control.cpp)
rospack_add_library(gazebo_battery src/gazebo_battery.cpp)
-rospack_add_library(Ros_Bumper src/Ros_Bumper.cc)
+rospack_add_library(ros_bumper src/ros_bumper.cpp)
-# This target requires adding player to the manifest.xml.
-#rospack_add_executable(player_pr2 src/player/Pr2_Player.cc)
-#target_link_libraries(player_pr2 playerc++)
-
rospack_add_rostest(test/test_slide.xml)
rospack_add_rostest(test/test_base.xml)
rospack_add_rostest(test/test_arm.xml)
@@ -35,10 +31,8 @@
rospack_add_rostest(test/hztest_rostime.xml)
rospack_add_rostest(test/hztest_pr2_odom.xml)
-# below need xvfb-run
-# test_camera seems to fail a lot
+# below need xvfb-run to test on build machine
rospack_add_rostest_graphical(test/test_camera.xml)
rospack_add_rostest_graphical(test/hztest_pr2_image.xml)
-rospack_add_executable(urdf2factory src/urdf2factory.cc)
-#rospack_add_executable(simiface src/simiface.cc)
+rospack_add_executable(urdf2factory src/urdf2factory.cpp)
Deleted: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/F3D.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/F3D.hh 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/F3D.hh 2008-12-24 17:55:10 UTC (rev 8571)
@@ -1,120 +0,0 @@
-/*
- * Gazebo - Outdoor Multi-Robot Simulator
- * Copyright (C) 2003
- * Nate Koenig & Andrew Howard
- *
- * This program is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation; either version 2 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program; if not, write to the Free Software
- * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
- *
- */
-/*
- * Desc: 3D Applied Force Feedback Interface
- * Author: John Hsu
- * Date: 24 Sept 2008
- * SVN: $Id$
- */
-#ifndef F3D_HH
-#define F3D_HH
-
-#include <gazebo/Controller.hh>
-#include <gazebo/Entity.hh>
-
-#include <ros/node.h>
-#include <rosthread/mutex.h>
-#include <std_msgs/Vector3Stamped.h>
-
-namespace gazebo
-{
-
-/// @addtogroup gazebo_dynamic_plugins Gazebo ROS Dynamic Plugins
-/// @{
-/** \defgroup F3D Applied Force Feedback Plugin XML Reference and Example
-
- \brief FIXME: Applied Force Feedback controller.
-
- This is a controller that gathers applied force data from a Body and populates a libgazebo interfaace as well as publish a ROS std_msgs::Vector3Stamped message (under topicName). This controller should only be used as a child of a Model. Below is an example of the usage of this plugin.
-
- \verbatim
- <model:physical name="camera_model">
- <controller:F3D name="f3d_finger_tip_l_left_controller" plugin="libF3D.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>100.0</updateRate>
- <bodyName>finger_tip_l_left</bodyName>
- <topicName>finger_tip_l_left_ground_truth</topicName>
- <frameName>map</frameName>
- <interface:position name="f3d_finger_tip_l_left_position" />
- </controller:F3D>
- </model:phyiscal>
- \endverbatim
-
-\{
-*/
-
-/// \brief F3D controller
-/// This is a controller that simulates a 6 dof position sensor
-class F3D : public Controller
-{
- /// \brief Constructor
- /// \param parent The parent entity must be a Model
- public: F3D(Entity *parent);
-
- /// \brief Destructor
- public: virtual ~F3D();
-
- /// \brief Load the controller
- /// \param node XML config node
- protected: virtual void LoadChild(XMLConfigNode *node);
-
- /// \brief Init the controller
- protected: virtual void InitChild();
-
- /// \brief Update the controller
- protected: virtual void UpdateChild();
-
- /// \brief Finalize the controller
- protected: virtual void FiniChild();
-
- /// \brief A link to the parent Model
- private: Model *myParent;
-
- /// \brief A pointer to the Gazebo Body
- private: Body *myBody;
-
-
- /// \brief A pointer to the ROS node. A node will be instantiated if it does not exist.
- private: ros::node *rosnode;
-
- /// \brief ROS Vector3Stamped message
- private: std_msgs::Vector3Stamped vector3Msg;
-
- /// \brief ROS Vector3Stamped topic name
- private: std::string topicName;
-
- /// \brief ROS frame transform name to use in the image message header.
- /// This should be simply map since the returned info is in Gazebo Global Frame.
- private: std::string frameName;
-
- /// \brief A mutex to lock access to fields that are used in message callbacks
- private: ros::thread::mutex lock;
-
-};
-
-/** \} */
-/// @}
-
-
-}
-
-#endif
-
Deleted: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/P3D.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/P3D.hh 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/P3D.hh 2008-12-24 17:55:10 UTC (rev 8571)
@@ -1,161 +0,0 @@
-/*
- * Gazebo - Outdoor Multi-Robot Simulator
- * Copyright (C) 2003
- * Nate Koenig & Andrew Howard
- *
- * This program is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation; either version 2 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program; if not, write to the Free Software
- * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
- *
- */
-/*
- * Desc: 3D position interface.
- * Author: Sachin Chitta and John Hsu
- * Date: 10 June 2008
- * SVN: $Id$
- */
-#ifndef P3D_HH
-#define P3D_HH
-
-#include <gazebo/Controller.hh>
-#include <gazebo/Entity.hh>
-
-#include <ros/node.h>
-#include <rosthread/mutex.h>
-#include <std_msgs/Pose3DStamped.h>
-#include <std_msgs/PoseWithRatesStamped.h>
-
-namespace gazebo
-{
-/// @addtogroup gazebo_dynamic_plugins Gazebo ROS Dynamic Plugins
-/// @{
- /** \defgroup P3D Groud Truth Position Pose and Rates Interface
-
- \brief P3D controller.
-
- This controller requires to a model as its parent. The plugin broadcasts a body's pose and rates through ROS std_msgs::PoseWithRatesStamped message. In the example below, the plubin broadcasts pose and rate of a body named \b body_name over ROS topic name \b body_pose_groud_truth.
-
- Example Usage:
- \verbatim
- <model:physical name="some_fancy_model">
- <controller:P3D name="p3d_controller" plugin="libP3D.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <bodyName>body_name</bodyName>
- <topicName>body_pose_ground_truth</topicName>
- <frameName>map</frameName>
- <xyzOffsets>25.65 25.65 0</xyzOffsets> <!-- option to initialize odometry for fake localization-->
- <rpyOffsets>0 0 0</rpyOffsets>
- <interface:position name="p3d_position_iface"/>
- </controller:P3D>
- </model:phyiscal>
- \endverbatim
-
-\{
-*/
-
-/**
-
- \brief P3D controller
- \li Starts a ROS node if none exists.
- \li This controller simulates a 6 dof position and rate sensor, publishes std_msgs::PoseWithRatesStamped.msg ROS topic.
- \li Example Usage:
- \verbatim
- <model:physical name="some_fancy_model">
- <controller:P3D name="p3d_controller" plugin="libP3D.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <bodyName>body_name</bodyName>
- <topicName>body_pose_ground_truth</topicName>
- <frameName>map</frameName>
- <xyzOffsets>25.65 25.65 0</xyzOffsets> <!-- option to initialize odometry for fake localization-->
- <rpyOffsets>0 0 0</rpyOffsets>
- <interface:position name="p3d_position_iface"/>
- </controller:P3D>
- </model:phyiscal>
- \endverbatim
- .
-*/
-
- class P3D : public Controller
- {
- /// \brief Constructor
- public: P3D(Entity *parent );
-
- /// \brief Destructor
- public: virtual ~P3D();
-
- /// \brief Load the controller
- /// \param node XML config node
- protected: virtual void LoadChild(XMLConfigNode *node);
-
- /// \brief Init the controller
- protected: virtual void InitChild();
-
- /// \brief Update the controller
- protected: virtual void UpdateChild();
-
- /// \brief Finalize the controller
- protected: virtual void FiniChild();
-
- /// \brief The parent Model
- private: Model *myParent;
-
- /// \brief The parent Model
- private: Body *myBody; //Gazebo/ODE body
-
-
-
- /// \brief pointer to ros node
- private: ros::node *rosnode;
-
- /// \brief ros message
- private: std_msgs::PoseWithRatesStamped poseMsg;
-
- /// \brief topic name
- private: std::string topicName;
-
- /// \brief frame transform name, should match link name
- /// FIXME: extract link name directly?
- private: std::string frameName;
-
- /// \brief allow specifying constant xyz and rpy offsets
- private: Vector3 xyzOffsets;
- private: Vector3 rpyOffsets;
-
- /// \brief A mutex to lock access to fields that are used in message callbacks
- private: ros::thread::mutex lock;
-
- /// \brief save last_time
- private: double last_time;
- private: Vector3 last_vpos;
- private: Vector3 last_veul;
- private: Vector3 apos;
- private: Vector3 aeul;
-
- /// \brief Gaussian noise
- private: double gaussianNoise;
-
- /// \brief Gaussian noise generator
- private: double GaussianKernel(double mu,double sigma);
-
- };
-
-/** \} */
-/// @}
-
-
-}
-
-#endif
-
Deleted: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Block_Laser.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Block_Laser.hh 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Block_Laser.hh 2008-12-24 17:55:10 UTC (rev 8571)
@@ -1,192 +0,0 @@
-/*
- * Gazebo - Outdoor Multi-Robot Simulator
- * Copyright (C) 2003
- * Nate Koenig & Andrew Howard
- *
- * This program is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation; either version 2 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program; if not, write to the Free Software
- * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
- *
- */
-/*
- * Desc: ros laser controller.
- * Author: Nathan Koenig
- * Date: 01 Feb 2007
- * SVN: $Id: Ros_Block_Laser.hh 6656 2008-06-20 22:52:19Z natepak $
- */
-
-#ifndef ROS_BLOCK_LASER_HH
-#define ROS_BLOCK_LASER_HH
-
-#include <gazebo/Controller.hh>
-
-#include <ros/node.h>
-#include <rosthread/mutex.h>
-#include <std_msgs/LaserScan.h>
-#include <std_msgs/PointCloud.h>
-
-namespace gazebo
-{
- class RaySensor;
-
-/// @addtogroup gazebo_dynamic_plugins Gazebo ROS Dynamic Plugins
-/// @{
-/** \defgroup Ros_Block_Laser ROS Block Laser Scanner Controller Plugin
-
- \brief ROS Block Laser Scanner Controller Plugin
-
- This is a controller that gathers range data from a ray sensor, and returns results via publishing ROS topic for point clouds.
-
- Example Usage:
- \verbatim
- <model:physical name="ray_model">
- <body:empty name="ray_body_name">
- <sensor:ray name="ray_sensor">
- <rayCount>30</rayCount>
- <rangeCount>30</rangeCount>
- <laserCount>1</laserCount>
-
- <origin>0.0 0.0 0.05</origin>
- <displayRays>false</displayRays>
-
- <minAngle>-15</minAngle>
- <maxAngle> 15</maxAngle>
-
- <minRange>0.05</minRange>
- <maxRange>100.0</maxRange>
- <updateRate>10.0</updateRate>
-
- <verticalRayCount>30</verticalRayCount>
- <verticalRangeCount>30</verticalRangeCount>
- <verticalMinAngle>-20</verticalMinAngle>
- <verticalMaxAngle> 0</verticalMaxAngle>
-
- <controller:ros_block_laser name="ray_block_controller" plugin="libRos_Block_Laser.so">
- <gaussianNoise>0.005</gaussianNoise>
- <alwaysOn>true</alwaysOn>
- <updateRate>10.0</updateRate>
- <topicName>full_cloud</topicName>
- <frameName>ray_model</frameName>
- <interface:laser name="ray_block_iface" />
- </controller:ros_block_laser>
- </sensor:ray>
- </body:empty>
- </model:phyiscal>
- \endverbatim
-
-\{
-*/
-
-/**
- \brief ROS laser block simulation.
- \li Starts a ROS node if none exists.
- \li This controller simulates a block of laser range detections.
- Resulting point cloud (std_msgs::PointCloud.msg) is published as a ROS topic.
- \li Example Usage:
- \verbatim
- <model:physical name="ray_model">
- <body:empty name="ray_body_name">
- <sensor:ray name="ray_sensor">
- <rayCount>30</rayCount>
- <rangeCount>30</rangeCount>
- <laserCount>1</laserCount>
-
- <origin>0.0 0.0 0.05</origin>
- <displayRays>false</displayRays>
-
- <minAngle>-15</minAngle>
- <maxAngle> 15</maxAngle>
-
- <minRange>0.05</minRange>
- <maxRange>100.0</maxRange>
- <updateRate>10.0</updateRate>
-
- <verticalRayCount>30</verticalRayCount>
- <verticalRangeCount>30</verticalRangeCount>
- <verticalMinAngle>-20</verticalMinAngle>
- <verticalMaxAngle> 0</verticalMaxAngle>
-
- <controller:ros_block_laser name="ray_block_controller" plugin="libRos_Block_Laser.so">
- <gaussianNoise>0.005</gaussianNoise>
- <alwaysOn>true</alwaysOn>
- <updateRate>10.0</updateRate>
- <topicName>full_cloud</topicName>
- <frameName>ray_model</frameName>
- <interface:laser name="ray_block_iface" />
- </controller:ros_block_laser>
- </sensor:ray>
- </body:empty>
- </model:phyiscal>
- \endverbatim
- .
-*/
-
-class Ros_Block_Laser : public Controller
-{
- /// \brief Constructor
- /// \param parent The parent entity, must be a Model or a Sensor
- public: Ros_Block_Laser(Entity *parent);
-
- /// \brief Destructor
- public: virtual ~Ros_Block_Laser();
-
- /// \brief Load the controller
- /// \param node XML config node
- protected: virtual void LoadChild(XMLConfigNode *node);
-
- /// \brief Init the controller
- protected: virtual void InitChild();
-
- /// \brief Update the controller
- protected: virtual void UpdateChild();
-
- /// \brief Finalize the controller
- protected: virtual void FiniChild();
-
- /// \brief Put laser data to the ROS topic
- private: void PutLaserData();
-
- /// \brief The parent sensor
- private: RaySensor *myParent;
-
- /// \brief pointer to ros node
- private: ros::node *rosnode;
-
- /// \brief ros message
- private: std_msgs::PointCloud cloudMsg;
-
- /// \brief topic name
- private: std::string topicName;
-
- /// \brief frame transform name, should match link name
- /// \brief FIXME: extract link name directly?
- private: std::string frameName;
-
- /// \brief Gaussian noise
- private: double gaussianNoise;
-
- /// \brief Gaussian noise generator
- private: double GaussianKernel(double mu,double sigma);
-
- /// \brief A mutex to lock access to fields that are used in message callbacks
- private: ros::thread::mutex lock;
-
-};
-
-/** \} */
-/// @}
-
-}
-
-#endif
-
Deleted: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Bumper.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Bumper.hh 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Bumper.hh 2008-12-24 17:55:10 UTC (rev 8571)
@@ -1,117 +0,0 @@
-/*
- * Gazebo - Outdoor Multi-Robot Simulator
- * Copyright (C) 2003
- * Nate Koenig & Andrew Howard
- *
- * This program is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation; either version 2 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program; if not, write to the Free Software
- * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
- *
- */
-/*
- * Desc: Bumper Controller
- * Author: Nate Koenig mod by John Hsu
- * Date: 24 Sept 2008
- */
-#ifndef ROS_BUMPER_CONTROLLER_HH
-#define ROS_BUMPER_CONTROLLER_HH
-
-#include <sys/time.h>
-
-#include <gazebo/Controller.hh>
-#include <gazebo/Entity.hh>
-#include <gazebo/Param.hh>
-
-// ros messages
-#include <ros/node.h>
-#include <rosthread/mutex.h>
-#include <std_msgs/String.h>
-
-namespace gazebo
-{
- class ContactSensor;
-
- /// \addtogroup gazebo_dynamic_plugins Gazebo ROS Dynamic Plugins
- /// \{
- /** \defgroup Ros_Bumper Ros Bumper Plugin
-
- \brief A controller that returns bump contacts
-
- \verbatim
- <model:physical name="camera_model">
- <body:empty name="camera_body_name">
- <sensor:contact name="finger_tip_l_left_contact_sensor">
- <updateRate>15.0</updateRate>
- <geom>pr2_finger_tip_l_collision_geom</geom>
- <controller:ros_bumper name="finger_tip_l_contact_controller" plugin="libRos_Bumper.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>15.0</updateRate>
- <topicName>finger_tip_l_contact</topicName>
- <frameName>finger_tip_l_contact</frameName>
- <interface:bumper name="dummy_bumper_iface" />
- </controller:ros_bumper>
- </sensor:contact>
- </body:empty>
- </model:phyiscal>
- \endverbatim
-
- \{
- */
-
- /// \brief A Bumper controller
- class Ros_Bumper : public Controller
- {
- /// Constructor
- public: Ros_Bumper(Entity *parent );
-
- /// Destructor
- public: virtual ~Ros_Bumper();
-
- /// Load the controller
- /// \param node XML config node
- protected: virtual void LoadChild(XMLConfigNode *node);
-
- /// Init the controller
- protected: virtual void InitChild();
-
- /// Update the controller
- protected: virtual void UpdateChild();
-
- /// Finalize the controller
- protected: virtual void FiniChild();
-
- /// The parent Model
- private: ContactSensor *myParent;
-
-
- /// \brief pointer to ros node
- private: ros::node *rosnode;
-
- /// \brief set topic name of broadcast
- private: ParamT<std::string> *bumperTopicNameP;
- private: std::string bumperTopicName;
-
- /// \brief A mutex to lock access to fields that are used in message callbacks
- private: ros::thread::mutex lock;
-
- /// \brief broadcast some string for now.
- private: std_msgs::String bumperMsg;
- };
-
- /** \} */
- /// \}
-
-}
-
-#endif
-
Deleted: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Camera.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Camera.hh 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Camera.hh 2008-12-24 17:55:10 UTC (rev 8571)
@@ -1,144 +0,0 @@
-/*
- * Gazebo - Outdoor Multi-Robot Simulator
- * Copyright (C) 2003
- * Nate Koenig & Andrew Howard
- *
- * This program is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation; either version 2 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program; if not, write to the Free Software
- * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
- *
- */
-/*
- * Desc: A dynamic controller plugin that publishes ROS image topic for generic camera sensor.
- * Author: John Hsu
- * Date: 24 Sept 2008
- * SVN: $Id$
- */
-#ifndef ROS_CAMERA_HH
-#define ROS_CAMERA_HH
-
-#include <ros/node.h>
-#include <rosthread/mutex.h>
-#include <std_msgs/Image.h>
-#include <gazebo/Controller.hh>
-
-namespace gazebo
-{
- class MonoCameraSensor;
-
-/// @addtogroup gazebo_dynamic_plugins Gazebo ROS Dynamic Plugins
-/// @{
-/** \defgroup Ros_Camera Ros Camera Plugin XML Reference and Example
-
- \brief Ros Camera Plugin Controller.
-
- This is a controller that collects data from a Camera Sensor and populates a libgazebo camera interface as well as publish a ROS std_msgs::Image (under the field \b \<topicName\>). This controller should only be used as a child of a camera sensor (see example below.
-
- Example Usage:
- \verbatim
- <model:physical name="camera_model">
- <body:empty name="camera_body_name">
- <sensor:camera name="camera_sensor">
- <controller:ros_camera name="controller-name" plugin="libRos_Camera.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>15.0</updateRate>
- <topicName>camera_name/image</topicName>
- <frameName>camera_body_name</frameName>
- </controller:ros_camera>
- </sensor:camera>
- </body:empty>
- </model:phyiscal>
- \endverbatim
-
-\{
-*/
-
-/**
-
-
- \brief Ros_Camera Controller.
- \li Starts a ROS node if none exists. \n
- \li Simulates a generic camera and broadcast std_msgs::Image topic over ROS.
- \li Example Usage:
- \verbatim
- <model:physical name="camera_model">
- <body:empty name="camera_body_name">
- <sensor:camera name="camera_sensor">
- <controller:ros_camera name="controller-name" plugin="libRos_Camera.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>15.0</updateRate>
- <topicName>camera_name/image</topicName>
- <frameName>camera_body_name</frameName>
- </controller:ros_camera>
- </sensor:camera>
- </body:empty>
- </model:phyiscal>
- \endverbatim
- .
-
-*/
-
-class Ros_Camera : public Controller
-{
- /// \brief Constructor
- /// \param parent The parent entity, must be a Model or a Sensor
- public: Ros_Camera(Entity *parent);
-
- /// \brief Destructor
- public: virtual ~Ros_Camera();
-
- /// \brief Load the controller
- /// \param node XML config node
- protected: virtual void LoadChild(XMLConfigNode *node);
-
- /// \brief Init the controller
- protected: virtual void InitChild();
-
- /// \brief Update the controller
- protected: virtual void UpdateChild();
-
- /// \brief Finalize the controller, unadvertise topics
- protected: virtual void FiniChild();
-
- /// \brief Put camera data to the ROS topic
- private: void PutCameraData();
-
- /// \brief A pointer to the parent camera sensor
- private: MonoCameraSensor *myParent;
-
- /// \brief A pointer to the ROS node. A node will be instantiated if it does not exist.
- private: ros::node *rosnode;
-
- /// \brief ROS image message
- private: std_msgs::Image imageMsg;
-
- /// \brief ROS image topic name
- private: std::string topicName;
-
- /// \brief ROS frame transform name to use in the image message header.
- /// This should typically match the link name the sensor is attached.
- private: std::string frameName;
-
- /// \brief A mutex to lock access to fields that are used in ROS message callbacks
- private: ros::thread::mutex lock;
-
- /// \brief size of image buffer
- private: uint32_t buf_size;
-};
-
-/** \} */
-/// @}
-
-}
-#endif
-
Deleted: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_JointForce.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_JointForce.hh 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_JointForce.hh 2008-12-24 17:55:10 UTC (rev 8571)
@@ -1,100 +0,0 @@
-/*
- * Gazebo - Outdoor Multi-Robot Simulator
- * Copyright (C) 2003
- * Nate Koenig & Andrew Howard
- *
- * This program is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation; either version 2 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program; if not, write to the Free Software
- * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
- *
- */
-/*
- * Desc: ROS Joint Force Controller
- * Author: John Hsu
- * Date: 24 Sept 2008
- */
-#ifndef ROS_JOINTFORCE_CONTROLLER_HH
-#define ROS_JOINTFORCE_CONTROLLER_HH
-
-/// Maximum number of joints that can be watched by one controller
-#define ROS_JOINTFORCE_CONTROLLER_MAX_FEEDBACKS 16
-
-#include "Controller.hh"
-#include "Entity.hh"
-#include <ode/ode.h>
-#include <sys/time.h>
-
-
-namespace gazebo
-{
-/// \addtogroup gazebo_dynamic_plugins Gazebo ROS Dynamic Plugins
-/// \{
-/** \defgroup Ros_Jointforce Joint Force Controller Plugin
-
- \brief A controller that measures forces and torques exerted by joints
-
- \verbatim
- <model:physical name="test_model">
- <body:empty name="body_name">
- <controller:ros_jointforce name="ros_ray_sensor_controller" plugin="libRos_Laser.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>15.0</updateRate>
- <topicName>jointfoce_topic_name</topicName>
- <frameName>test_model</frameName>
- <interface:opaque name="jointforce_iface" />
- </controller:ros_jointforce>
- </body:empty>
- </model:phyiscal>
- \endverbatim
-
- \{
-*/
-
-/// \brief A JointForce controller
-class Ros_JointForce : public Controller
-{
- /// \brief Constructor
- public: Ros_JointForce(Entity *parent );
-
- /// \brief Destructor
- public: virtual ~Ros_JointForce();
-
- /// \brief Load the controller
- /// \param node XML config node
- protected: virtual void LoadChild(XMLConfigNode *node);
-
- /// \brief Init the controller
- protected: virtual void InitChild();
-
- /// \brief Update the controller
- protected: virtual void UpdateChild();
-
- /// \brief Finalize the controller
- protected: virtual void FiniChild();
-
- /// \brief The parent Model
- private: Model *myParent;
-
- /// \brief The joint feedbacks
- private: dJointFeedback *jointfeedbacks[ROS_JOINTFORCE_CONTROLLER_MAX_FEEDBACKS];
- /// \brief The number of joints we are watching
- private: int n_joints;
-};
-
-/** \} */
-/// \}
-
-}
-
-#endif
-
Deleted: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Laser.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Laser.hh 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Laser.hh 2008-12-24 17:55:10 UTC (rev 8571)
@@ -1,172 +0,0 @@
-/*
- * Gazebo - Outdoor Multi-Robot Simulator
- * Copyright (C) 2003
- * Nate Koenig & Andrew Howard
- *
- * This program is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation; either version 2 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program; if not, write to the Free Software
- * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
- *
- */
-/*
- * Desc: ROS laser controller.
- * Author: John Hsu
- * Date: 24 Sept 2007
- * SVN: $Id$
- */
-
-#ifndef ROS_LASER_HH
-#define ROS_LASER_HH
-
-#include <gazebo/Controller.hh>
-
-#include <ros/node.h>
-#include <rosthread/mutex.h>
-#include <std_msgs/LaserScan.h>
-
-namespace gazebo
-{
- class RaySensor;
-
-/// @addtogroup gazebo_dynamic_plugins Gazebo ROS Dynamic Plugins
-/// @{
-/** \defgroup Ros_Laser ROS Laser Scanner Controller Plugin
-
- \brief ROS Laser Scanner Controller Plugin
-
- This controller gathers range data from a simulated ray sensor, publishes range data through
- std_msgs::LaserScan ROS topic.
-
- Example Usage:
- \verbatim
- <model:physical name="ray_model">
- <body:empty name="ray_body_name">
- <sensor:ray name="ray_sensor">
- <origin>0.0 0.0 0.0</origin>
- <rayCount>683</rayCount>
- <rangeCount>683</rangeCount>
- <laserCount>1</laserCount>
- <displayRays>false</displayRays>
- <minAngle>-45</minAngle>
- <maxAngle> 45</maxAngle>
- <minRange>0.05</minRange>
- <maxRange>10.0</maxRange>
- <updateRate>10.0</updateRate>
- <controller:ros_laser name="ros_ray_sensor_controller" plugin="libRos_Laser.so">
- <gaussianNoise>0.005</gaussianNoise>
- <alwaysOn>true</alwaysOn>
- <updateRate>15.0</updateRate>
- <topicName>ray_scan</topicName>
- <frameName>ray_model</frameName>
- <interface:laser name="ros_ray_sensor_iface" />
- </controller:ros_laser>
- </sensor:ray>
- </body:empty>
- </model:phyiscal>
- \endverbatim
-
-\{
-*/
-
-/**
- \brief ROS laser scan controller.
- \li Starts a ROS node if none exists.
- \li Simulates a laser range sensor and publish std_msgs::LaserScan.msg over ROS.
- \li Example Usage:
- \verbatim
- <model:physical name="ray_model">
- <body:empty name="ray_body_name">
- <sensor:ray name="ray_sensor">
- <origin>0.0 0.0 0.0</origin>
- <rayCount>683</rayCount>
- <rangeCount>683</rangeCount>
- <laserCount>1</laserCount>
- <displayRays>false</displayRays>
- <minAngle>-45</minAngle>
- <maxAngle> 45</maxAngle>
- <minRange>0.05</minRange>
- <maxRange>10.0</maxRange>
- <updateRate>10.0</updateRate>
- <controller:ros_laser name="ros_ray_sensor_controller" plugin="libRos_Laser.so">
- <gaussianNoise>0.005</gaussianNoise>
- <alwaysOn>true</alwaysOn>
- <updateRate>15.0</updateRate>
- <topicName>ray_scan</topicName>
- <frameName>ray_model</frameName>
- <interface:laser name="ros_ray_sensor_iface" />
- </controller:ros_laser>
- </sensor:ray>
- </body:empty>
- </model:phyiscal>
- \endverbatim
- .
-*/
-
-class Ros_Laser : public Controller
-{
- /// \brief Constructor
- /// \param parent The parent entity, must be a Model or a Sensor
- public: Ros_Laser(Entity *parent);
-
- /// \brief Destructor
- public: virtual ~Ros_Laser();
-
- /// \brief Load the controller
- /// \param node XML config node
- protected: virtual void LoadChild(XMLConfigNode *node);
-
- /// \brief Init the controller
- protected: virtual void InitChild();
-
- /// \brief Update the controller
- protected: virtual void UpdateChild();
-
- /// \brief Finalize the controller
- protected: virtual void FiniChild();
-
- /// \brief Put laser data to the ROS topic
- private: void PutLaserData();
-
- /// \brief The parent sensor
- private: RaySensor *myParent;
-
- /// \brief pointer to ros node
- private: ros::node *rosnode;
-
- /// \brief ros message
- private: std_msgs::LaserScan laserMsg;
-
- /// \brief topic name
- private: std::string topicName;
-
- /// \brief frame transform name, should match link name
- private: std::string frameName;
-
- /// \brief Gaussian noise
- private: double gaussianNoise;
-
- /// \brief Gaussian noise generator
- private: double GaussianKernel(double mu,double sigma);
-
- /// \brief A mutex to lock access to fields that are used in message callbacks
- private: ros::thread::mutex lock;
-
-};
-
-/** \} */
-/// @}
-
-}
-
-#endif
-
Deleted: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_PTZ.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_PTZ.hh 2008-12-24 07:51:50 UTC (rev 8570)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_PTZ.hh 2008-12-24 17:55:10 UTC (rev 8571)
@@ -1,176 +0,0 @@
-/*
- * Gazebo - Outdoor Multi-Robot Simulator
- * Copyright (C) 2003
- * Nate Koenig & Andrew Howard
- *
- * This program is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation; either version 2 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program; if not, write to the Free Software
- * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
- *
- */
-/*
- * Desc: A ros ptz controller
- * Author: Nathan Koenig
- * Date: 26 Nov 2007
- * SVN: $Id$
- */
-
-#ifndef ROS_PTZ_HH
-#define ROS_PTZ_HH
-
-#include <gazebo/Param.hh>
-#include <gazebo/Controller.hh>
-
-// ros messages
-#include <ros/node.h>
-#include <rosthread/mutex.h>
-
-// messages for controlling ptz
-#include <axis_cam/PTZActuatorState.h>
-#include <axis_cam/PTZActuatorCmd.h>
-
-namespace gazebo
-{
- class HingeJoint;
-
-/// @addtogroup gazebo_dynamic_plugins Gazebo ROS Dynamic Plugins
-/// @{
-/** \defgroup Ros_PTZ ROS PTZ Camera Controller Plugin
-
- \brief ROS pan-tilt-zoom controller.
-
- This is a controller that controls a pan, tilt, zoom unit
-
- Example Usage:
- \verbatim
- <model:physical name="ptz_model">
- <controller:Ros_PTZ name="ptz_controller" plugin="libRos_PTZ.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>15.0</updateRate>
- <panJoint>ptz_pan_joint_name</panJoint>
- <tiltJoint>ptz_tilt_joint_name</tiltJoint>
- <commandTopicName>camera_name/ptz_cmd</commandTopicName>
- <stateTopicName>camera_name/ptz_state</stateTopicName>
- <interface:ptz name="ptz_iface" />
- </controller:Ros_PTZ>
- </model:phyiscal>
- \endverbatim
-
-\{
-*/
-
-/**
-
- \brief ROS Pan/Tilt/Zoom Camera Controller
- \li Starts a ROS node if none exists.
- \li Simulates PTZ camera actuators.
- - publish state information (PT angles) to ROS topic: \e camera_name/ptz_state
- - subscribe to ROS topic: \e camera_name/ptz_cmd
- \li Example Usage:
- \verbatim
- <model:physical name="ptz_model">
- <controller:Ros_PTZ name="ptz_controller" plugin="libRos_PTZ.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>15.0</updateRate>
- <panJoint>ptz_pan_joint_name</panJoint>
- <tiltJoint>ptz_tilt_joint_name</tiltJoint>
- <commandTopicName>camera_name/ptz_cmd</commandTopicName>
- <stateTopicName>camera_name/ptz_state</stateTopicName>
- <interface:ptz name="ptz_iface" />
- </controller:Ros_PTZ>
- </model:phyiscal>
- \endverbatim
- .
-*/
- class Ros_PTZ : public Controller
- {
- /// \brief Constructor
- /// \param parent The parent entity, must be a Model or a Sensor
- public: Ros_PTZ(Entity *parent);
-
- /// \brief Destructor
- public: virtual ~Ros_PTZ();
-
- /// \brief Load the controller
- /// \param node XML config node
- protected: virtual void LoadChild(XMLConfigNode *node);
-
- /// \brief Save the controller.
- /// stream Output stream
- protected: void SaveChild(std::string &prefix, std::ostream &stream);
-
- /// \brief Init the controller
- protected: virtual void InitChild();
-
- /// \brief Update the controller
- protected: virtual void UpdateChild();
-
- /// \brief Finalize the controller
- protected: virtual void FiniChild();
-
- /// \brief Reset the controller
- protected: virtual void ResetChild();
-
- /// \brief Put camera data to the ROS topic
- private: void PutPTZData();
-
- /// \brief The parent sensor
- private: Model *myParent;
-
- /// \brief Pan joint
- private: HingeJoint *panJoint;
-
- /// \brief Tilt joint
- private: HingeJoint *tiltJoint;
-
- private: float cmdTilt;
- private: float cmdPan;
-
- private: ParamT<double> *motionGainP;
- private: ParamT<double> *forceP;
-
- private: ParamT<std::string> *panJointNameP;
- private: ParamT<std::string> *tiltJointNameP;
- private: ParamT<std::string> *commandTopicNameP;
- private: ParamT<std::string> *stateTopicNameP;
-
- /// \brief pointer to ros node
- private: ros::node *rosnode;
- /// \brief ros message
- private: axis_cam::PTZActuatorState PTZStateMessage;
- private: axis_cam::PTZActuatorCmd PTZControlMessage;
-
- /// \brief receive message
- private: void PTZCommandReceived();
-
- /// \brief topic name
- private: std::string commandTopicName;
- private: std::string stateTopicName;
-
- /// \brief frame transform name, should match link name
- /// \brief FIXME: extract link name directly? currently using joint names
- private: std::string panFrameName;
- private: std::string tiltFrameName;
-
- /// \brief A mutex to lock access to fields that are used in message callbacks
- private: ros::thread::mutex lock;
-
- };
-
- /** \} */
- /// @}
-
-}
-
-#endif
-
Deleted: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Stereo_Camera.hh
===================================================================
-...
[truncated message content] |