|
From: <hsu...@us...> - 2008-09-10 00:04:44
|
Revision: 4127
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4127&view=rev
Author: hsujohnhsu
Date: 2008-09-10 00:04:54 +0000 (Wed, 10 Sep 2008)
Log Message:
-----------
add flag <alwaysOn> to allow continuous on operation for controllers in Gazebo w/o Iface connection.
Modified Paths:
--------------
pkg/trunk/3rdparty/gazebo/gazebo_patch.diff
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml
Modified: pkg/trunk/3rdparty/gazebo/gazebo_patch.diff
===================================================================
--- pkg/trunk/3rdparty/gazebo/gazebo_patch.diff 2008-09-09 23:14:57 UTC (rev 4126)
+++ pkg/trunk/3rdparty/gazebo/gazebo_patch.diff 2008-09-10 00:04:54 UTC (rev 4127)
@@ -904,6 +904,20 @@
private: friend class DestroyerT<World>;
private: friend class SingletonT<World>;
};
+Index: server/controllers/Controller.hh
+===================================================================
+--- server/controllers/Controller.hh (revision 7016)
++++ server/controllers/Controller.hh (working copy)
+@@ -105,6 +105,9 @@
+ /// \brief The entity that owns this controller
+ protected: Entity *parent;
+
++ /// \breif flag to keep controllers updating continuously
++ protected: ParamT<bool> *alwaysOnP;
++
+ /// \brief Update period
+ protected: double updatePeriod;
+ protected: ParamT<double> *updatePeriodP;
Index: server/controllers/camera/generic/Generic_Camera.cc
===================================================================
--- server/controllers/camera/generic/Generic_Camera.cc (revision 7016)
@@ -938,13 +952,33 @@
===================================================================
--- server/controllers/Controller.cc (revision 7016)
+++ server/controllers/Controller.cc (working copy)
-@@ -75,11 +75,15 @@
+@@ -43,6 +43,7 @@
+ {
+ Param::Begin(&this->parameters);
+ this->nameP = new ParamT<std::string>("name","",1);
++ this->alwaysOnP = new ParamT<bool>("alwaysOn", false, 0);
+ this->updatePeriodP = new ParamT<double>("updateRate", 10, 0);
+ Param::End();
+
+@@ -60,6 +61,7 @@
+ {
+ this->Fini();
+ delete this->nameP;
++ delete this->alwaysOnP;
+ delete this->updatePeriodP;
+ }
+
+@@ -75,10 +77,17 @@
this->typeName = node->GetName();
this->nameP->Load(node);
+
++ this->alwaysOnP->Load(node);
++
this->updatePeriodP->Load(node);
- this->updatePeriod = 1.0 / (this->updatePeriodP->GetValue() + 1e-6);
+
+- this->lastUpdate = -1e6;
+ double updateRate = this->updatePeriodP->GetValue();
+ if (updateRate == 0)
+ this->updatePeriod = 0.0; // no throttling if updateRate is 0
@@ -952,11 +986,17 @@
+ this->updatePeriod = 1.0 / updateRate;
+ this->lastUpdate = Simulator::Instance()->GetSimTime();
-- this->lastUpdate = -1e6;
--
childNode = node->GetChildByNSPrefix("interface");
- // Create the interfaces
+@@ -178,7 +187,7 @@
+ /// Update the controller. Called every cycle.
+ void Controller::Update()
+ {
+- if (this->IsConnected())
++ if (this->IsConnected() || this->alwaysOnP->GetValue())
+ {
+ if (lastUpdate + updatePeriod <= Simulator::Instance()->GetSimTime())
+ {
Index: server/controllers/ptz/generic/Generic_PTZ.cc
===================================================================
--- server/controllers/ptz/generic/Generic_PTZ.cc (revision 7016)
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo.xml 2008-09-09 23:14:57 UTC (rev 4126)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo.xml 2008-09-10 00:04:54 UTC (rev 4127)
@@ -9,11 +9,12 @@
<!-- PR2_ACTARRAY -->
<controller:gazebo_actuators name="gazebo_actuators" plugin="libgazebo_actuators.so">
- <updateRate>100.0</updateRate>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
- <robot filename="pr2_gazebo_actuators.xml" />
+ <robot filename="pr2_gazebo_actuators.xml" />
- <interface:audio name="gazebo_actuators_dummy_iface" />
+ <interface:audio name="gazebo_actuators_dummy_iface" />
</controller:gazebo_actuators>
</verbatim>
@@ -25,6 +26,7 @@
<!-- ptz camera controls -->
<controller:generic_ptz name="ptz_cam_left_controller">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_left_joint</panJoint>
<tiltJoint>ptz_tilt_left_joint</tiltJoint>
@@ -32,6 +34,7 @@
</controller:generic_ptz>
<controller:generic_ptz name="ptz_cam_right_controller">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_right_joint</panJoint>
<tiltJoint>ptz_tilt_right_joint</tiltJoint>
@@ -40,27 +43,30 @@
<!-- P3D for position groundtruth -->
<controller:P3D name="p3d_right_wrist_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>gripper_roll_right</bodyName>
- <topicName>gripper_roll_right_pose</topicName>
- <frameName>gripper_roll_right_frame</frameName>
- <interface:position name="p3d_right_wrist_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>gripper_roll_right</bodyName>
+ <topicName>gripper_roll_right_pose</topicName>
+ <frameName>gripper_roll_right_frame</frameName>
+ <interface:position name="p3d_right_wrist_position"/>
</controller:P3D>
<controller:P3D name="p3d_left_wrist_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>gripper_roll_left</bodyName>
- <topicName>gripper_roll_left_pose</topicName>
- <frameName>gripper_roll_left_frame</frameName>
- <interface:position name="p3d_left_wrist_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>gripper_roll_left</bodyName>
+ <topicName>gripper_roll_left_pose</topicName>
+ <frameName>gripper_roll_left_frame</frameName>
+ <interface:position name="p3d_left_wrist_position"/>
</controller:P3D>
<controller:P3D name="p3d_base_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>base</bodyName>
- <topicName>base_pose</topicName>
- <frameName>base_frame</frameName>
- <interface:position name="p3d_base_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>base</bodyName>
+ <topicName>base_pose</topicName>
+ <frameName>base_frame</frameName>
+ <interface:position name="p3d_base_position"/>
</controller:P3D>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml 2008-09-09 23:14:57 UTC (rev 4126)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml 2008-09-10 00:04:54 UTC (rev 4127)
@@ -10,15 +10,16 @@
<!-- PR2_ACTARRAY -->
<!-- uncomment for testing -->
<controller:test_actuators name="test_actuators" plugin="libtest_actuators.so">
- <updateRate>100.0</updateRate>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
- <!-- used exclusively by test_actuators to find out where these files are, in combination with env var MC_RESOURCE_PATH -->
- <include>gazebo_joints.xml</include>
- <robot_filename>pr2_test_actuators.xml</robot_filename>
- <controller_filename>controllers.xml</controller_filename>
- <actuator_filename>actuators.xml</actuator_filename>
+ <!-- used exclusively by test_actuators to find out where these files are, in combination with env var MC_RESOURCE_PATH -->
+ <include>gazebo_joints.xml</include>
+ <robot_filename>pr2_test_actuators.xml</robot_filename>
+ <controller_filename>controllers.xml</controller_filename>
+ <actuator_filename>actuators.xml</actuator_filename>
- <interface:audio name="test_actuators_dummy_iface" />
+ <interface:audio name="test_actuators_dummy_iface" />
</controller:test_actuators>
</verbatim>
@@ -30,6 +31,7 @@
<!-- ptz camera controls -->
<controller:Ros_PTZ name="ptz_cam_left_controller" plugin="libRos_PTZ.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_left_joint</panJoint>
<tiltJoint>ptz_tilt_left_joint</tiltJoint>
@@ -39,6 +41,7 @@
</controller:Ros_PTZ>
<controller:Ros_PTZ name="ptz_cam_right_controller" plugin="libRos_PTZ.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_right_joint</panJoint>
<tiltJoint>ptz_tilt_right_joint</tiltJoint>
@@ -49,27 +52,30 @@
<!-- P3D for position groundtruth -->
<controller:P3D name="p3d_right_wrist_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>gripper_roll_right</bodyName>
- <topicName>gripper_roll_right_pose</topicName>
- <frameName>gripper_roll_right_frame</frameName>
- <interface:position name="p3d_right_wrist_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>gripper_roll_right</bodyName>
+ <topicName>gripper_roll_right_pose</topicName>
+ <frameName>gripper_roll_right_frame</frameName>
+ <interface:position name="p3d_right_wrist_position"/>
</controller:P3D>
<controller:P3D name="p3d_left_wrist_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>gripper_roll_left</bodyName>
- <topicName>gripper_roll_left_pose</topicName>
- <frameName>gripper_roll_left_frame</frameName>
- <interface:position name="p3d_left_wrist_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>gripper_roll_left</bodyName>
+ <topicName>gripper_roll_left_pose</topicName>
+ <frameName>gripper_roll_left_frame</frameName>
+ <interface:position name="p3d_left_wrist_position"/>
</controller:P3D>
<controller:P3D name="p3d_base_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>base</bodyName>
- <topicName>base_pose</topicName>
- <frameName>base_frame</frameName>
- <interface:position name="p3d_base_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>base</bodyName>
+ <topicName>base_pose</topicName>
+ <frameName>base_frame</frameName>
+ <interface:position name="p3d_base_position"/>
</controller:P3D>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml 2008-09-09 23:14:57 UTC (rev 4126)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml 2008-09-10 00:04:54 UTC (rev 4127)
@@ -10,6 +10,7 @@
<!-- PR2_ACTARRAY -->
<!-- uncomment for testing -->
<controller:test_actuators name="test_actuators" plugin="libtest_actuators.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>1000.0</updateRate>
<!-- used exclusively by test_actuators to find out where these files are, in combination with env var MC_RESOURCE_PATH -->
@@ -30,6 +31,7 @@
<!-- ptz camera controls -->
<controller:Ros_PTZ name="ptz_cam_left_controller" plugin="libRos_PTZ.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_left_joint</panJoint>
<tiltJoint>ptz_tilt_left_joint</tiltJoint>
@@ -39,6 +41,7 @@
</controller:Ros_PTZ>
<controller:Ros_PTZ name="ptz_cam_right_controller" plugin="libRos_PTZ.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_right_joint</panJoint>
<tiltJoint>ptz_tilt_right_joint</tiltJoint>
@@ -49,27 +52,30 @@
<!-- P3D for position groundtruth -->
<controller:P3D name="p3d_right_wrist_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>gripper_roll_right</bodyName>
- <topicName>gripper_roll_right_pose</topicName>
- <frameName>gripper_roll_right_frame</frameName>
- <interface:position name="p3d_right_wrist_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>gripper_roll_right</bodyName>
+ <topicName>gripper_roll_right_pose</topicName>
+ <frameName>gripper_roll_right_frame</frameName>
+ <interface:position name="p3d_right_wrist_position"/>
</controller:P3D>
<controller:P3D name="p3d_left_wrist_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>gripper_roll_left</bodyName>
- <topicName>gripper_roll_left_pose</topicName>
- <frameName>gripper_roll_left_frame</frameName>
- <interface:position name="p3d_left_wrist_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>gripper_roll_left</bodyName>
+ <topicName>gripper_roll_left_pose</topicName>
+ <frameName>gripper_roll_left_frame</frameName>
+ <interface:position name="p3d_left_wrist_position"/>
</controller:P3D>
<controller:P3D name="p3d_base_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>base</bodyName>
- <topicName>base_pose</topicName>
- <frameName>base_frame</frameName>
- <interface:position name="p3d_base_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>base</bodyName>
+ <topicName>base_pose</topicName>
+ <frameName>base_frame</frameName>
+ <interface:position name="p3d_base_position"/>
</controller:P3D>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml 2008-09-09 23:14:57 UTC (rev 4126)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml 2008-09-10 00:04:54 UTC (rev 4127)
@@ -1755,6 +1755,7 @@
<maxRange>10.0</maxRange>
<updateRate>10.0</updateRate>
<controller:ros_laser name="ros_tilt_laser_controller" plugin="libRos_Laser.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>tilt_scan</topicName>
<frameName>tilt_laser</frameName>
@@ -1816,6 +1817,7 @@
<maxRange>10.0</maxRange>
<updateRate>10.0</updateRate>
<controller:ros_laser name="ros_base_laser_controller" plugin="libRos_Laser.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>10</updateRate>
<topicName>base_scan</topicName>
<frameName>base_laser</frameName>
@@ -1873,6 +1875,7 @@
<farClip>100</farClip>
<updateRate>15.0</updateRate>
<controller:ros_camera name="wrist_cam_left_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>image_wrist_left</topicName>
<frameName>wrist_camera_left</frameName>
@@ -1880,6 +1883,7 @@
</controller:ros_camera>
<!--
<controller:generic_camera name="wrist_cam_left_controller">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<interface:camera name="wrist_cam_left_iface_1" />
</controller:generic_camera>
@@ -1936,6 +1940,7 @@
<farClip>100</farClip>
<updateRate>15.0</updateRate>
<controller:ros_camera name="wrist_cam_right_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>image_wrist_right</topicName>
<frameName>wrist_camera_right</frameName>
@@ -1943,6 +1948,7 @@
</controller:ros_camera>
<!--
<controller:generic_camera name="wrist_cam_right_controller">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<interface:camera name="wrist_cam_right_iface_1" />
</controller:generic_camera>
@@ -1999,6 +2005,7 @@
<farClip>100</farClip>
<updateRate>15.0</updateRate>
<controller:ros_camera name="forearm_cam_left_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>image_forearm_left</topicName>
<frameName>forearm_roll_left</frameName>
@@ -2056,6 +2063,7 @@
<farClip>100</farClip>
<updateRate>15.0</updateRate>
<controller:ros_camera name="forearm_cam_right_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>image_forearm_right</topicName>
<frameName>forearm_roll_right</frameName>
@@ -2143,6 +2151,7 @@
<farClip>100</farClip>
<updateRate>15.0</updateRate>
<controller:ros_camera name="ptz_cam_left_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>PTZL_image</topicName>
<frameName>ptz_left</frameName>
@@ -2231,6 +2240,7 @@
<farClip>100</farClip>
<updateRate>15.0</updateRate>
<controller:ros_camera name="ptz_cam_right_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>PTZR_image</topicName>
<frameName>ptz_right</frameName>
@@ -2296,6 +2306,7 @@
<baseline>0.2</baseline>
<updateRate>15.0</updateRate>
<controller:stereocamera name="stereo_camera_controller">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<interface:stereocamera name="stereo_iface_0" />
<interface:camera name="camera_iface_0" />
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|