|
From: <hsu...@us...> - 2008-09-29 15:57:52
|
Revision: 4762
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4762&view=rev
Author: hsujohnhsu
Date: 2008-09-29 15:57:25 +0000 (Mon, 29 Sep 2008)
Log Message:
-----------
more udpates on documentation for plugins.
Modified Paths:
--------------
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_Camera.hh
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Laser.hh
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Time.hh
pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/P3D.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/P3D.hh 2008-09-29 07:39:29 UTC (rev 4761)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/P3D.hh 2008-09-29 15:57:25 UTC (rev 4762)
@@ -44,7 +44,7 @@
\brief P3D controller.
- This controller requires to a model as its parent. The plugin broadcasts a specific body's pose and rates through a ROS TransformWithRateSTamped message as well as filling out a PositionIface.
+ This controller requires to a model as its parent. The plugin broadcasts a body's pose and rates through ROS std_msgs::TransformWithRateStamped message as well as filling out a Gazebo::PositionIface. 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.
\verbatim
<model:physical name="some_fancy_model">
@@ -65,7 +65,8 @@
*/
/// \brief P3D controller
- /// This is a controller that simulates a 6 dof position sensor
+ /// \li Starts a ROS node if none exists.
+ /// \li This controller simulates a 6 dof position and rate sensor.
class P3D : public Controller
{
/// \brief Constructor
Modified: 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-09-29 07:39:29 UTC (rev 4761)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Block_Laser.hh 2008-09-29 15:57:25 UTC (rev 4762)
@@ -87,8 +87,9 @@
\{
*/
-/// \brief ros laser controller.
-/// This is a controller that simulates a ros laser
+/// \brief ROS laser block simulation.
+/// \li Starts a ROS node if none exists.
+/// \li This controller simulates a block of laser range detections.
class Ros_Block_Laser : public Controller
{
/// \brief Constructor
Modified: 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-09-29 07:39:29 UTC (rev 4761)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Camera.hh 2008-09-29 15:57:25 UTC (rev 4762)
@@ -42,7 +42,7 @@
\brief Ros Camera Plugin Controller.
- This is a controller that collects data from a Camera Sensor and populates a libgazebo camera interfaace as well as publish a ROS std_msgs::Image (under topicName). This controller should only be used as a child of a camera sensor
+ 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.
\verbatim
<model:physical name="camera_model">
@@ -63,8 +63,9 @@
\{
*/
-/// \brief Ros_Camera Plugin Controller
-/// This is a controller that simulates a generic camera
+/// \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. \n
class Ros_Camera : public Controller
{
/// \brief Constructor
Modified: 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-09-29 07:39:29 UTC (rev 4761)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Laser.hh 2008-09-29 15:57:25 UTC (rev 4762)
@@ -45,7 +45,8 @@
\brief ROS Laser Scanner Controller Plugin
- This is a controller that gathers range data from a ray sensor, and returns results via publishing ROS topic and Iface.
+ This controller gathers range data from a simulated ray sensor, publishes range data through
+ std_msgs::LaserScan ROS topic and Gazebo Iface.
\verbatim
<model:physical name="ray_model">
@@ -77,8 +78,9 @@
\{
*/
-/// \brief ros laser controller.
-/// This is a controller that simulates a ros laser
+/// \brief ROS laser scan controller.
+/// \li Starts a ROS node if none exists.
+/// \li Simulates a laser range sensor.
class Ros_Laser : public Controller
{
/// \brief Constructor
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Time.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Time.hh 2008-09-29 07:39:29 UTC (rev 4761)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Time.hh 2008-09-29 15:57:25 UTC (rev 4762)
@@ -69,8 +69,8 @@
\{
*/
-/// \brief starts a ROS time node and broadcast simulator time
-/// This is a controller that starts a ros time
+/// \brief Starts a ROS node if none exists and broadcast simulator time
+/// over rostools::Time.
class Ros_Time : public Controller
{
/// \brief Constructor
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world 2008-09-29 07:39:29 UTC (rev 4761)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world 2008-09-29 15:57:25 UTC (rev 4762)
@@ -54,7 +54,7 @@
<material>Gazebo/CloudySky</material>
</sky>
<gazeboPath>media</gazeboPath>
- <grid>off</grid>
+ <grid>false</grid>
<maxUpdateRate>100</maxUpdateRate>
</rendering:ogre>
@@ -145,10 +145,10 @@
<rpy> 0.0 0.0 0.00</rpy>
<body:box name="slide1_legs_body">
<geom:box name="slide_base_geom">
- <kp>1000000000000000</kp>
+ <kp>10000000000000000</kp>
<kd>1</kd>
- <mu1>0.0</mu1>
- <mu2>0.0</mu2>
+ <mu1>10000.0</mu1>
+ <mu2>10000.0</mu2>
<xyz> 0.0 5.0 13</xyz>
<rpy> 45.0 0.0 0.00</rpy>
@@ -156,7 +156,7 @@
<mass> 1000.0</mass>
<visual>
<size>2.0 14.14 1.0</size>
- <material>Gazebo/Rocky</material>
+ <material>Gazebo/Red</material>
<mesh>unit_box</mesh>
</visual>
</geom:box>
@@ -225,8 +225,8 @@
<geom:box name="support_1">
<kp>10000000.0</kp>
<kd>1</kd>
- <mu1>0.0</mu1>
- <mu2>0.0</mu2>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
<xyz>1000.0 1000.0 1.00</xyz>
<rpy> 0.0 0.0 0.00</rpy>
<mesh>default</mesh>
@@ -241,8 +241,8 @@
<geom:box name="support_2">
<kp>10000000.0</kp>
<kd>1</kd>
- <mu1>0.0</mu1>
- <mu2>0.0</mu2>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
<xyz>1000.0 -1000.0 1.00</xyz>
<rpy> 0.0 0.0 0.00</rpy>
<mesh>default</mesh>
@@ -257,8 +257,8 @@
<geom:box name="support_3">
<kp>10000000.0</kp>
<kd>1</kd>
- <mu1>0.0</mu1>
- <mu2>0.0</mu2>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
<xyz>-1000.0 -1000.0 1.00</xyz>
<rpy> 0.0 0.0 0.00</rpy>
<mesh>default</mesh>
@@ -273,8 +273,8 @@
<geom:box name="support_4">
<kp>10000000.0</kp>
<kd>1</kd>
- <mu1>0.0</mu1>
- <mu2>0.0</mu2>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
<xyz>-1000.0 1000.0 1.00</xyz>
<rpy> 0.0 0.0 0.00</rpy>
<mesh>default</mesh>
@@ -334,7 +334,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 8.0 50.0 </xyz>
+ <xyz>0.0 8.0 110.0 </xyz>
<rpy>0.0 0.0 90.0 </rpy>
<!-- base, torso and arms -->
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|