|
From: <hsu...@us...> - 2008-11-21 21:03:20
|
Revision: 7160
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7160&view=rev
Author: hsujohnhsu
Date: 2008-11-21 21:03:16 +0000 (Fri, 21 Nov 2008)
Log Message:
-----------
* more name change correction for tilt_laser to laser_tilt.
* also updated visualization camera topic names from axis_left to axis_l and similarly for others.
* update frame name references in highlevel_controller to laser_tilt_link.
* update stereo to stereo_link for sensor link in pr2_robot_defs.
Modified Paths:
--------------
pkg/trunk/demos/pr2_gazebo/controllers_2dnav_test.xml
pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/cfg/launch_gazebo.xml
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/cfg/launch_gazebo_obstacle.xml
pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/head_defs.xml
pkg/trunk/visualization/pr2_gui/src/pr2_gui/pr2_frame.py
Modified: pkg/trunk/demos/pr2_gazebo/controllers_2dnav_test.xml
===================================================================
--- pkg/trunk/demos/pr2_gazebo/controllers_2dnav_test.xml 2008-11-21 20:51:28 UTC (rev 7159)
+++ pkg/trunk/demos/pr2_gazebo/controllers_2dnav_test.xml 2008-11-21 21:03:16 UTC (rev 7160)
@@ -212,10 +212,10 @@
</controller>
<!-- this version of laser scanner controller seems to be broken
- <controller name="tilt_laser_controller" topic="laser_test" type="LaserScannerControllerNode">
+ <controller name="laser_tilt_mount_controller" topic="laser_test" type="LaserScannerControllerNode">
<velocity>
<velocityFilter smoothing="0.2"/>
- <joint name="tilt_laser_mount_joint" type="velocity">
+ <joint name="laser_tilt_mount_joint" type="velocity">
<pid p="0.56" i = "14" d = "0.000001" iClamp = "0.02" />
</joint>
</velocity>
Modified: pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch
===================================================================
--- pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch 2008-11-21 20:51:28 UTC (rev 7159)
+++ pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch 2008-11-21 21:03:16 UTC (rev 7160)
@@ -8,6 +8,9 @@
<node pkg="mechanism_control" type="spawner.py" args="$(find pr2_alpha)/controllers_base_lab.xml" output="screen"/>
<node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/pr2_prototype1/controllers_head_laser_tilt_torso_gazebo.xml" output="screen"/>
+ <!-- PR2 Calibration -->
+ <!--include file="$(find wg_robot_description)/pr2_prototype1/calibrate.launch" /-->
+
<!-- send laser tilt motor a command -->
<!--node pkg="pr2_mechanism_controllers" type="control_laser.py" args="laser_tilt_controller sine 20 0.872 0.3475" respawn="false" output="screen" /-->
<node pkg="pr2_mechanism_controllers" type="control_laser.py" args="laser_tilt_controller sine 1 .45 .40" />
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/cfg/launch_gazebo.xml
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/cfg/launch_gazebo.xml 2008-11-21 20:51:28 UTC (rev 7159)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/cfg/launch_gazebo.xml 2008-11-21 21:03:16 UTC (rev 7160)
@@ -4,7 +4,7 @@
<node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/pr2/controllers.xml" respawn="false" output="screen" />
- <node pkg="robot_mechanism_controllers" type="control.py" args="set tilt_laser_controller 46" respawn="false" output="screen" />
+ <node pkg="robot_mechanism_controllers" type="control.py" args="set laser_tilt_controller 46" respawn="false" output="screen" />
<node pkg="map_server" type="map_server" args="$(find gazebo_robot_description)/world/Media/materials/textures/map3.png 0.1" respawn="false" />
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/cfg/launch_gazebo_obstacle.xml
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/cfg/launch_gazebo_obstacle.xml 2008-11-21 20:51:28 UTC (rev 7159)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/cfg/launch_gazebo_obstacle.xml 2008-11-21 21:03:16 UTC (rev 7160)
@@ -6,7 +6,7 @@
<node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/pr2/controllers.xml" respawn="false" output="screen" />
- <node pkg="robot_mechanism_controllers" type="control.py" args="set tilt_laser_controller 46" respawn="false" output="screen" />
+ <node pkg="robot_mechanism_controllers" type="control.py" args="set laser_tilt_controller 46" respawn="false" output="screen" />
<node pkg="map_server" type="map_server" args="$(find gazebo_robot_description)/world/Media/materials/textures/map3.png 0.1" respawn="false" />
<node pkg="amcl_player" type="amcl_player" args="scan:=base_scan" respawn="false" />
Modified: pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp 2008-11-21 20:51:28 UTC (rev 7159)
+++ pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp 2008-11-21 21:03:16 UTC (rev 7160)
@@ -123,10 +123,9 @@
robotWidth_ = inscribedRadius * 2;
// Allocate observation buffers
-
tf::TransformListener *tempTf_ = new tf::TransformListener(*this, true, (uint64_t)10000000000ULL);
baseScanBuffer_ = new costmap_2d::BasicObservationBuffer(std::string("base_laser"), *tempTf_, ros::Duration(0, 0), inscribedRadius, minZ_, maxZ_);
- tiltScanBuffer_ = new costmap_2d::BasicObservationBuffer(std::string("tilt_laser"), *tempTf_, ros::Duration(1, 0), inscribedRadius, minZ_, maxZ_);
+ tiltScanBuffer_ = new costmap_2d::BasicObservationBuffer(std::string("laser_tilt_link"), *tempTf_, ros::Duration(1, 0), inscribedRadius, minZ_, maxZ_);
stereoCloudBuffer_ = new costmap_2d::BasicObservationBuffer(std::string("stereo"), *tempTf_, ros::Duration(0, 0), inscribedRadius, minZ_, maxZ_);
// get map via RPC
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/head_defs.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/head_defs.xml 2008-11-21 20:51:28 UTC (rev 7159)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/head_defs.xml 2008-11-21 21:03:16 UTC (rev 7160)
@@ -155,19 +155,19 @@
<map name="sensor" flag="gazebo">
<verbatim key="sensor_${name}_camera">
- <sensor:camera name="${name}_left_sensor">
+ <sensor:camera name="${name}_l_sensor">
<imageWidth>640</imageWidth>
<imageHeight>480</imageHeight>
<hfov>60</hfov>
<nearClip>0.1</nearClip>
<farClip>100</farClip>
<updateRate>20.0</updateRate>
- <controller:ros_camera name="${name}_left_controller" plugin="libRos_Camera.so">
+ <controller:ros_camera name="${name}_l_controller" plugin="libRos_Camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>20.0</updateRate>
- <topicName>${name}_left/image</topicName>
- <frameName>${name}</frameName>
- <interface:camera name="${name}_left_iface" />
+ <topicName>${name}_l/image</topicName>
+ <frameName>${name}_link</frameName>
+ <interface:camera name="${name}_l_iface" />
</controller:ros_camera>
</sensor:camera>
</verbatim>
@@ -199,7 +199,7 @@
<alwaysOn>true</alwaysOn>
<updateRate>10.0</updateRate>
<topicName>full_cloud</topicName>
- <frameName>${name}</frameName>
+ <frameName>${name}_link</frameName>
<interface:laser name="${name}_laser_iface" />
</controller:ros_block_laser>
</sensor:ray>
Modified: pkg/trunk/visualization/pr2_gui/src/pr2_gui/pr2_frame.py
===================================================================
--- pkg/trunk/visualization/pr2_gui/src/pr2_gui/pr2_frame.py 2008-11-21 20:51:28 UTC (rev 7159)
+++ pkg/trunk/visualization/pr2_gui/src/pr2_gui/pr2_frame.py 2008-11-21 21:03:16 UTC (rev 7160)
@@ -99,11 +99,11 @@
self._aui_manager.AddPane(self._monitor_panel, wx.aui.AuiPaneInfo().BottomDockable().Bottom().Layer(1).BestSize(wx.Size(700,600)).Name('runtime_monitor').Caption('Runtime Monitor'), 'Runtime Monitor')
self._aui_manager.AddPane(self._hardware_panel, wx.aui.AuiPaneInfo().BottomDockable().Bottom().Layer(1).BestSize(wx.Size(300,200)).Name('hardware').Caption('Hardware'), 'Hardware')
- self.add_camera_pane("forearm_right", False)
- self.add_camera_pane("forearm_left", False)
- self.add_camera_pane("axis_right", True)
- self.add_camera_pane("axis_left", True)
- self.add_camera_pane("stereo_left", False)
+ self.add_camera_pane("forearm_r", False)
+ self.add_camera_pane("forearm_l", False)
+ self.add_camera_pane("axis_r", True)
+ self.add_camera_pane("axis_l", True)
+ self.add_camera_pane("stereo_l", False)
self._aui_manager.Update()
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|