|
From: <hsu...@us...> - 2008-12-18 03:20:43
|
Revision: 8317
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=8317&view=rev
Author: hsujohnhsu
Date: 2008-12-18 03:20:40 +0000 (Thu, 18 Dec 2008)
Log Message:
-----------
* pr2_prototype1 now using laser_tilt controller xml for laser_tilt controller
* renamed laser_controller to laser_tilt_controller (update corresponding launch scripts)
* added ransac stuff in 2dnav_gazebo
* using hw time in laser scanner controller (thanks Vijay)
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp
pkg/trunk/demos/2dnav_gazebo/2dnav-stack-amcl.xml
pkg/trunk/demos/2dnav_gazebo/2dnav-stack-fake_localization.xml
pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_controllers.launch
pkg/trunk/robot_descriptions/wg_robot_description/laser_tilt/laser_tilt_controller.xml
pkg/trunk/world_models/ransac_ground_plane_extraction/test_ground_plane.launch
Added Paths:
-----------
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_torso_gazebo.xml
Removed Paths:
-------------
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_laser_tilt_torso_gazebo.xml
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp 2008-12-18 03:18:26 UTC (rev 8316)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp 2008-12-18 03:20:40 UTC (rev 8317)
@@ -495,6 +495,7 @@
{
if (publisher_->trylock())
{
+ publisher_->msg_.header.stamp = ros::Time((uint64_t) (c_->getTime()*1000000000)) ;
publisher_->msg_.signal = m_scanner_signal_.signal ;
publisher_->unlockAndPublish() ;
need_to_send_msg_ = false ;
@@ -547,6 +548,7 @@
bool LaserScannerControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
{
+
service_prefix_ = config->Attribute("name");
if (!c_->initXml(robot, config))
Modified: pkg/trunk/demos/2dnav_gazebo/2dnav-stack-amcl.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/2dnav-stack-amcl.xml 2008-12-18 03:18:26 UTC (rev 8316)
+++ pkg/trunk/demos/2dnav_gazebo/2dnav-stack-amcl.xml 2008-12-18 03:20:40 UTC (rev 8317)
@@ -37,7 +37,27 @@
-->
<!-- starting ransac node -->
- <node pkg="ransac_ground_plane_extraction" type="ransacnode" output="screen" />
+ <node pkg="point_cloud_assembler" type="point_cloud_assembler" output="screen" name="assembler">
+ <remap from="scan" to="tilt_scan"/>
+ <param name="ignore_laser_skew" type="bool" value="true" />
+ </node>
+ <node pkg="point_cloud_assembler" type="point_cloud_snapshotter" output="screen" name="snapshotter">
+ <remap from="laser_scanner_signal" to="laser_tilt_controller/laser_scanner_signal"/>
+ <remap from="full_cloud" to="tilt_scan_cloud" />
+ <param name="fixed_frame" type="string" value="base_link" />
+ </node>
+ <param name="ransac_ground_plane_extraction/listen_topic" value="tilt_scan_cloud"/>
+ <param name="ransac_ground_plane_extraction/publish_ground_plane_topic" value="ground_plane"/>
+ <param name="ransac_ground_plane_extraction/publish_obstacle_topic" value="obstacle_cloud"/>
+ <param name="ransac_ground_plane_extraction/min_ignore_distance" value="-0.13"/>
+ <param name="ransac_ground_plane_extraction/max_ignore_distance" value="0.07"/>
+ <param name="ransac_ground_plane_extraction/distance_threshold" value="0.03"/>
+ <param name="ransac_ground_plane_extraction/far_remove_distance_threshold" value="0.06"/>
+ <param name="ransac_ground_plane_extraction/far_remove_distance" value="6.0"/>
+ <param name="ransac_ground_plane_extraction/filter_delta" value="1.0"/>
+ <param name="ransac_ground_plane_extraction/max_ransac_iterations" value="500"/>
+ <param name="ransac_ground_plane_extraction/publish_obstacle_cloud" type="string" value="yes"/>
+ <node pkg="ransac_ground_plane_extraction" type="ransacnode" respawn="false" output="screen" />
<!-- filter out veil effect from range scans -->
<param name="/scan_shadows_filter/filter_min_angle" value="10"/>
@@ -83,7 +103,7 @@
<node pkg="highlevel_controllers" type="recharge_controller" respawn="false" />
<!-- For logging distance traveled -->
- <node pkg="rosrecord" type="rosrecord" args="-f /bags/robot_runs/milestone_trials/attempt /base_scan /tilt_scan /TransformArray /localizedpose /odom /base_controller/odometer /odom_estimation" />
+ <node pkg="rosrecord" type="rosrecord" args="-f /tmp/robot_runs/milestone_trials/attempt /base_scan /tilt_scan /TransformArray /localizedpose /odom /base_controller/odometer /odom_estimation" />
<!-- For telling the robot to go charge -->
<node pkg="highlevel_controllers" type="joy_batt_sender" respawn="true" />
Modified: pkg/trunk/demos/2dnav_gazebo/2dnav-stack-fake_localization.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/2dnav-stack-fake_localization.xml 2008-12-18 03:18:26 UTC (rev 8316)
+++ pkg/trunk/demos/2dnav_gazebo/2dnav-stack-fake_localization.xml 2008-12-18 03:20:40 UTC (rev 8317)
@@ -32,7 +32,27 @@
-->
<!-- starting ransac node -->
- <node pkg="ransac_ground_plane_extraction" type="ransacnode" output="screen" />
+ <node pkg="point_cloud_assembler" type="point_cloud_assembler" output="screen" name="assembler">
+ <remap from="scan" to="tilt_scan"/>
+ <param name="ignore_laser_skew" type="bool" value="true" />
+ </node>
+ <node pkg="point_cloud_assembler" type="point_cloud_snapshotter" output="screen" name="snapshotter">
+ <remap from="laser_scanner_signal" to="laser_tilt_controller/laser_scanner_signal"/>
+ <remap from="full_cloud" to="tilt_scan_cloud" />
+ <param name="fixed_frame" type="string" value="base_link" />
+ </node>
+ <param name="ransac_ground_plane_extraction/listen_topic" value="tilt_scan_cloud"/>
+ <param name="ransac_ground_plane_extraction/publish_ground_plane_topic" value="ground_plane"/>
+ <param name="ransac_ground_plane_extraction/publish_obstacle_topic" value="obstacle_cloud"/>
+ <param name="ransac_ground_plane_extraction/min_ignore_distance" value="-0.13"/>
+ <param name="ransac_ground_plane_extraction/max_ignore_distance" value="0.07"/>
+ <param name="ransac_ground_plane_extraction/distance_threshold" value="0.03"/>
+ <param name="ransac_ground_plane_extraction/far_remove_distance_threshold" value="0.06"/>
+ <param name="ransac_ground_plane_extraction/far_remove_distance" value="6.0"/>
+ <param name="ransac_ground_plane_extraction/filter_delta" value="1.0"/>
+ <param name="ransac_ground_plane_extraction/max_ransac_iterations" value="500"/>
+ <param name="ransac_ground_plane_extraction/publish_obstacle_cloud" type="string" value="yes"/>
+ <node pkg="ransac_ground_plane_extraction" type="ransacnode" respawn="false" output="screen" />
<!-- move_base_sbpl settings -->
<!-- for the moment use e.g.: ./shparam set move_base/plannerType string ADPlanner -->
@@ -72,7 +92,7 @@
<node pkg="highlevel_controllers" type="recharge_controller" respawn="false" />
<!-- For logging distance traveled -->
- <node pkg="rosrecord" type="rosrecord" args="-f /bags/robot_runs/milestone_trials/attempt /base_scan /tilt_scan /TransformArray /localizedpose /odom /base_controller/odometer /odom_estimation" />
+ <node pkg="rosrecord" type="rosrecord" args="-f /tmp/robot_runs/milestone_trials/attempt /base_scan /tilt_scan /TransformArray /localizedpose /odom /base_controller/odometer /odom_estimation" />
<!-- For telling the robot to go charge -->
<node pkg="highlevel_controllers" type="joy_batt_sender" respawn="true" />
Modified: pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_controllers.launch
===================================================================
--- pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_controllers.launch 2008-12-18 03:18:26 UTC (rev 8316)
+++ pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_controllers.launch 2008-12-18 03:20:40 UTC (rev 8317)
@@ -2,10 +2,12 @@
<!-- use mech.py to spawn all controllers listed in controllers.xml -->
<param name="base_controller/odom_publish_rate" value="10" />
<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"/>
+ <node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/pr2_prototype1/controllers_head_torso_gazebo.xml" output="screen"/>
+
<!-- start tilting Hokuyo laser by sending it a preset code of 46, this means sawtooth profile sweep.
for details of the profile, rates, see controller::LaserScannerControllerNode. -->
<!--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" />
+ <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" />
</launch>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/laser_tilt/laser_tilt_controller.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/laser_tilt/laser_tilt_controller.xml 2008-12-18 03:18:26 UTC (rev 8316)
+++ pkg/trunk/robot_descriptions/wg_robot_description/laser_tilt/laser_tilt_controller.xml 2008-12-18 03:20:40 UTC (rev 8317)
@@ -1,5 +1,5 @@
<controllers>
- <controller name="laser_controller" topic="laser_controller" type="LaserScannerControllerNode">
+ <controller name="laser_tilt_controller" topic="laser_tilt_controller" type="LaserScannerControllerNode">
<filter smoothing_factor="0.1" />
<joint name="laser_tilt_mount_joint">
<pid p="12" i=".1" d="1" iClamp="0.5" />
Deleted: pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_laser_tilt_torso_gazebo.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_laser_tilt_torso_gazebo.xml 2008-12-18 03:18:26 UTC (rev 8316)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_laser_tilt_torso_gazebo.xml 2008-12-18 03:20:40 UTC (rev 8317)
@@ -1,34 +0,0 @@
-<?xml version="1.0"?>
-
-<controllers>
-
-
- <!-- ========================================= -->
- <!-- torso_lift array -->
- <controller name="torso_lift_controller" topic="torso_lift_controller" type="JointPositionControllerNode">
- <joint name="torso_lift_joint">
- <pid p="1000" d="0" i="1" iClamp="100" />
- </joint>
- </controller>
- <!-- ========================================= -->
- <!-- head and above array -->
- <controller name="head_pan_controller" topic="head_pan_controller" type="JointPositionControllerNode">
- <listen_topic name="head_pan_commands" />
- <joint name="head_pan_joint" >
- <pid p="100" d="0" i="0" iClamp="0" />
- </joint>
- </controller>
- <controller name="head_tilt_controller" topic="head_tilt_controller" type="JointPositionControllerNode">
- <listen_topic name="head_tilt_commands" />
- <joint name="head_tilt_joint" >
- <pid p="100" d="0" i="0" iClamp="0" />
- </joint>
- </controller>
-
- <controller name="laser_tilt_controller" topic="laser_tilt_controller" type="LaserScannerControllerNode">
- <joint name="laser_tilt_mount_joint" >
- <pid p="12" i=".1" d="1" iClamp="0.5" />
- </joint>
- </controller>
-
-</controllers>
Copied: pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_torso_gazebo.xml (from rev 8315, pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_laser_tilt_torso_gazebo.xml)
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_torso_gazebo.xml (rev 0)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_torso_gazebo.xml 2008-12-18 03:20:40 UTC (rev 8317)
@@ -0,0 +1,28 @@
+<?xml version="1.0"?>
+
+<controllers>
+
+
+ <!-- ========================================= -->
+ <!-- torso_lift array -->
+ <controller name="torso_lift_controller" topic="torso_lift_controller" type="JointPositionControllerNode">
+ <joint name="torso_lift_joint">
+ <pid p="1000" d="0" i="1" iClamp="100" />
+ </joint>
+ </controller>
+ <!-- ========================================= -->
+ <!-- head and above array -->
+ <controller name="head_pan_controller" topic="head_pan_controller" type="JointPositionControllerNode">
+ <listen_topic name="head_pan_commands" />
+ <joint name="head_pan_joint" >
+ <pid p="100" d="0" i="0" iClamp="0" />
+ </joint>
+ </controller>
+ <controller name="head_tilt_controller" topic="head_tilt_controller" type="JointPositionControllerNode">
+ <listen_topic name="head_tilt_commands" />
+ <joint name="head_tilt_joint" >
+ <pid p="100" d="0" i="0" iClamp="0" />
+ </joint>
+ </controller>
+
+</controllers>
Modified: pkg/trunk/world_models/ransac_ground_plane_extraction/test_ground_plane.launch
===================================================================
--- pkg/trunk/world_models/ransac_ground_plane_extraction/test_ground_plane.launch 2008-12-18 03:18:26 UTC (rev 8316)
+++ pkg/trunk/world_models/ransac_ground_plane_extraction/test_ground_plane.launch 2008-12-18 03:20:40 UTC (rev 8317)
@@ -2,7 +2,7 @@
<launch>
<group name="wg">
<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_controller sine 2 .45 .40" />
+ <node pkg="pr2_mechanism_controllers" type="control_laser.py" args="laser_tilt_controller sine 2 .45 .40" />
<node pkg="point_cloud_assembler" type="point_cloud_assembler" output="screen" name="assembler">
<remap from="scan" to="tilt_scan"/>
@@ -10,11 +10,11 @@
</node>
<node pkg="point_cloud_assembler" type="point_cloud_snapshotter" output="screen" name="snapshotter">
- <remap from="laser_scanner_signal" to="laser_controller/laser_scanner_signal"/>
+ <remap from="laser_scanner_signal" to="laser_tilt_controller/laser_scanner_signal"/>
<param name="fixed_frame" type="string" value="base_link" />
</node>
- <param name="ransac_ground_plane_extraction/listen_topic" value="full_cloud"/>
+ <param name="ransac_ground_plane_extraction/listen_topic" value="tilt_scan_cloud"/>
<param name="ransac_ground_plane_extraction/publish_ground_plane_topic" value="ground_plane"/>
<param name="ransac_ground_plane_extraction/publish_obstacle_topic" value="obstacle_cloud"/>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|