|
From: <ei...@us...> - 2009-08-27 21:43:47
|
Revision: 23180
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23180&view=rev
Author: eitanme
Date: 2009-08-27 21:43:37 +0000 (Thu, 27 Aug 2009)
Log Message:
-----------
Adding the robot self filter to the navigation stack. Also, updating launch files on pre so that the robot actually works. Hopefully, this will save other people a lot of pain.
Modified Paths:
--------------
pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/config/lasers_and_filters.xml
pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/manifest.xml
pkg/trunk/demos/2dnav_gazebo/config/lasers_and_filters.launch
pkg/trunk/demos/2dnav_gazebo/manifest.xml
pkg/trunk/demos/milestone2/milestone2_actions/config/perception.xml
pkg/trunk/demos/milestone2/milestone2_actions/manifest.xml
pkg/trunk/sandbox/3dnav_pr2/launch/pr2_planning_environment.launch
pkg/trunk/stacks/pr2/pr2_alpha/pre.launch
pkg/trunk/stacks/pr2/pr2_alpha/pre.machine
Modified: pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/config/lasers_and_filters.xml
===================================================================
--- pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/config/lasers_and_filters.xml 2009-08-27 21:41:34 UTC (rev 23179)
+++ pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/config/lasers_and_filters.xml 2009-08-27 21:43:37 UTC (rev 23180)
@@ -1,4 +1,7 @@
<launch>
+
+<include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
+
<node pkg="mux" type="throttle" args="3.0 base_scan base_scan_throttled" />
<node pkg="mux" type="throttle" args="3.0 tilt_scan tilt_scan_throttled" />
<node pkg="mux" type="throttle" args="3.0 tilt_scan_filtered tilt_scan_filtered_throttled" />
@@ -12,16 +15,124 @@
<rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
<rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="tilt_scan" />
- <param name="cloud_topic" value="tilt_scan_filtered" />
+ <param name="cloud_topic" value="tilt_scan_shadow_filtered" />
<param name="high_fidelity" value="true" />
</node>
+<!-- Filter for tilt laser scans that hit the body of the robot -->
+<node pkg="robot_self_filter" type="self_filter" name="tilt_laser_self_filter" respawn="true" output="screen">
+
+ <!-- The topic for the input cloud -->
+ <remap from="cloud_in" to="tilt_scan_shadow_filtered" />
+
+ <!-- The topic for the output cloud -->
+ <remap from="cloud_out" to="tilt_scan_filtered" />
+
+ <!-- The frame of the sensor used to obtain the data to be
+ filtered; This parameter is optional. If it is not specified,
+ shadow points will be considered outside -->
+ <param name="sensor_frame" type="string" value="laser_tilt_link" />
+
+ <!-- Minimum distance to sensor (for point not to be considered inside) -->
+ <param name="min_sensor_dist" type="double" value="0.01" />
+
+ <!-- The padding to be added for the body parts the robot can see -->
+ <param name="self_see_padd" type="double" value="0.05" />
+
+ <!-- The scaling to be added for the body parts the robot can see -->
+ <param name="self_see_scale" type="double" value="1.0" />
+
+ <!-- The names of the links the sensor can see -->
+ <param name="self_see_links" type="string" value="l_upper_arm_link
+ l_upper_arm_roll_link
+ l_elbow_flex_link
+ l_forearm_link
+ l_forearm_roll_link
+ l_wrist_flex_link
+ l_wrist_roll_link
+ l_gripper_l_finger_link
+ l_gripper_l_finger_tip_link
+ l_gripper_r_finger_link
+ l_gripper_r_finger_tip_link
+ l_shoulder_pan_link
+ l_shoulder_lift_link
+ r_upper_arm_link
+ r_upper_arm_roll_link
+ r_elbow_flex_link
+ r_forearm_link
+ r_forearm_roll_link
+ r_wrist_flex_link
+ r_wrist_roll_link
+ r_gripper_l_finger_link
+ r_gripper_l_finger_tip_link
+ r_gripper_r_finger_link
+ r_gripper_r_finger_tip_link
+ r_shoulder_pan_link
+ r_shoulder_lift_link
+ base_laser
+ base_link" />
+
+</node>
+
<!-- Filter for base laser shadowing/veiling -->
<node pkg="laser_scan" type="scan_to_cloud" respawn="true" machine="three" name="base_shadow_filter" >
<rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
<rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="base_scan" />
- <param name="cloud_topic" value="base_scan_marking" />
+ <param name="cloud_topic" value="base_scan_shadow_filtered" />
</node>
+<!-- Filter for base laser scans that hit the body of the robot -->
+<node pkg="robot_self_filter" type="self_filter" name="base_laser_self_filter" respawn="true" output="screen">
+
+ <!-- The topic for the input cloud -->
+ <remap from="cloud_in" to="base_scan_shadow_filtered" />
+
+ <!-- The topic for the output cloud -->
+ <remap from="cloud_out" to="base_scan_marking" />
+
+ <!-- The frame of the sensor used to obtain the data to be
+ filtered; This parameter is optional. If it is not specified,
+ shadow points will be considered outside -->
+ <param name="sensor_frame" type="string" value="base_laser" />
+
+ <!-- Minimum distance to sensor (for point not to be considered inside) -->
+ <param name="min_sensor_dist" type="double" value="0.01" />
+
+ <!-- The padding to be added for the body parts the robot can see -->
+ <param name="self_see_padd" type="double" value="0.01" />
+
+ <!-- The scaling to be added for the body parts the robot can see -->
+ <param name="self_see_scale" type="double" value="1.0" />
+
+ <!-- The names of the links the sensor can see -->
+ <param name="self_see_links" type="string" value="l_upper_arm_link
+ l_upper_arm_roll_link
+ l_elbow_flex_link
+ l_forearm_link
+ l_forearm_roll_link
+ l_wrist_flex_link
+ l_wrist_roll_link
+ l_gripper_l_finger_link
+ l_gripper_l_finger_tip_link
+ l_gripper_r_finger_link
+ l_gripper_r_finger_tip_link
+ l_shoulder_pan_link
+ l_shoulder_lift_link
+ r_upper_arm_link
+ r_upper_arm_roll_link
+ r_elbow_flex_link
+ r_forearm_link
+ r_forearm_roll_link
+ r_wrist_flex_link
+ r_wrist_roll_link
+ r_gripper_l_finger_link
+ r_gripper_l_finger_tip_link
+ r_gripper_r_finger_link
+ r_gripper_r_finger_tip_link
+ r_shoulder_pan_link
+ r_shoulder_lift_link" />
+
+</node>
+
</launch>
Modified: pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/manifest.xml
===================================================================
--- pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/manifest.xml 2009-08-27 21:41:34 UTC (rev 23179)
+++ pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/manifest.xml 2009-08-27 21:43:37 UTC (rev 23180)
@@ -19,6 +19,8 @@
<depend package="mux"/>
<depend package="backup_safetysound"/>
<depend package="geometry_msgs"/>
+ <depend package="robot_self_filter"/>
+ <depend package="3dnav_pr2"/>
<!-- packages used in the test scripts -->
<depend package="robot_actions"/>
Modified: pkg/trunk/demos/2dnav_gazebo/config/lasers_and_filters.launch
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/config/lasers_and_filters.launch 2009-08-27 21:41:34 UTC (rev 23179)
+++ pkg/trunk/demos/2dnav_gazebo/config/lasers_and_filters.launch 2009-08-27 21:43:37 UTC (rev 23180)
@@ -1,4 +1,7 @@
<launch>
+
+<include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
+
<node pkg="mechanism_control" type="spawner.py" args="$(find pr2_experimental_controllers)/laser_tilt/laser_tilt_controller.xml" />
<node pkg="pr2_mechanism_controllers" type="send_periodic_cmd.py" args="laser_tilt_controller linear 2 .65 .25" />
@@ -35,25 +38,128 @@
</node>
<!-- Filter for tilt laser shadowing/veiling -->
-<!-- subscribes tilt_scan and publishes tilt_scan_filtered -->
-<node pkg="laser_scan" type="scan_shadows_filter_node" respawn="true" machine="three" name="tilt_shadow_filter">
+<node pkg="laser_scan" type="scan_to_cloud" respawn="true" machine="three" name="tilt_shadow_filter">
+ <rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
+ <rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="tilt_scan" />
- <param name="cloud_topic" value="tilt_scan_filtered" />
+ <param name="cloud_topic" value="tilt_scan_shadow_filtered" />
+ <param name="high_fidelity" value="true" />
</node>
+<!-- Filter for tilt laser scans that hit the body of the robot -->
+<node pkg="robot_self_filter" type="self_filter" name="tilt_laser_self_filter" respawn="true" output="screen">
+
+ <!-- The topic for the input cloud -->
+ <remap from="cloud_in" to="tilt_scan_shadow_filtered" />
+
+ <!-- The topic for the output cloud -->
+ <remap from="cloud_out" to="tilt_scan_filtered" />
+
+ <!-- The frame of the sensor used to obtain the data to be
+ filtered; This parameter is optional. If it is not specified,
+ shadow points will be considered outside -->
+ <param name="sensor_frame" type="string" value="laser_tilt_link" />
+
+ <!-- Minimum distance to sensor (for point not to be considered inside) -->
+ <param name="min_sensor_dist" type="double" value="0.01" />
+
+ <!-- The padding to be added for the body parts the robot can see -->
+ <param name="self_see_padd" type="double" value="0.01" />
+
+ <!-- The scaling to be added for the body parts the robot can see -->
+ <param name="self_see_scale" type="double" value="1.0" />
+
+ <!-- The names of the links the sensor can see -->
+ <param name="self_see_links" type="string" value="l_upper_arm_link
+ l_upper_arm_roll_link
+ l_elbow_flex_link
+ l_forearm_link
+ l_forearm_roll_link
+ l_wrist_flex_link
+ l_wrist_roll_link
+ l_gripper_l_finger_link
+ l_gripper_l_finger_tip_link
+ l_gripper_r_finger_link
+ l_gripper_r_finger_tip_link
+ l_shoulder_pan_link
+ l_shoulder_lift_link
+ r_upper_arm_link
+ r_upper_arm_roll_link
+ r_elbow_flex_link
+ r_forearm_link
+ r_forearm_roll_link
+ r_wrist_flex_link
+ r_wrist_roll_link
+ r_gripper_l_finger_link
+ r_gripper_l_finger_tip_link
+ r_gripper_r_finger_link
+ r_gripper_r_finger_tip_link
+ r_shoulder_pan_link
+ r_shoulder_lift_link
+ base_laser
+ base_link" />
+
+</node>
+
<!-- Filter for base laser shadowing/veiling -->
-<node pkg="laser_scan" type="scan_shadows_filter_node" respawn="true" machine="three" name="base_shadow_filter_non_preserve" >
+<node pkg="laser_scan" type="scan_to_cloud" respawn="true" machine="three" name="base_shadow_filter" >
+ <rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
+ <rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="base_scan" />
- <param name="cloud_topic" value="base_scan_marking" />
- <param name="laser_max_range" value="30.0" />
+ <param name="cloud_topic" value="base_scan_shadow_filtered" />
</node>
-<!-- for clearing we want preservative -->
-<node pkg="laser_scan" type="scan_shadows_filter_node" respawn="true" machine="three" name="base_shadow_filter_preserve" >
- <param name="scan_topic" value="base_scan" />
- <param name="cloud_topic" value="base_scan_clearing" />
- <param name="preservative" value="true" />
- <param name="laser_max_range" value="30.0" />
+<!-- Filter for base laser scans that hit the body of the robot -->
+<node pkg="robot_self_filter" type="self_filter" name="base_laser_self_filter" respawn="true" output="screen">
+
+ <!-- The topic for the input cloud -->
+ <remap from="cloud_in" to="base_scan_shadow_filtered" />
+
+ <!-- The topic for the output cloud -->
+ <remap from="cloud_out" to="base_scan_marking" />
+
+ <!-- The frame of the sensor used to obtain the data to be
+ filtered; This parameter is optional. If it is not specified,
+ shadow points will be considered outside -->
+ <param name="sensor_frame" type="string" value="base_laser" />
+
+ <!-- Minimum distance to sensor (for point not to be considered inside) -->
+ <param name="min_sensor_dist" type="double" value="0.01" />
+
+ <!-- The padding to be added for the body parts the robot can see -->
+ <param name="self_see_padd" type="double" value="0.01" />
+
+ <!-- The scaling to be added for the body parts the robot can see -->
+ <param name="self_see_scale" type="double" value="1.0" />
+
+ <!-- The names of the links the sensor can see -->
+ <param name="self_see_links" type="string" value="l_upper_arm_link
+ l_upper_arm_roll_link
+ l_elbow_flex_link
+ l_forearm_link
+ l_forearm_roll_link
+ l_wrist_flex_link
+ l_wrist_roll_link
+ l_gripper_l_finger_link
+ l_gripper_l_finger_tip_link
+ l_gripper_r_finger_link
+ l_gripper_r_finger_tip_link
+ l_shoulder_pan_link
+ l_shoulder_lift_link
+ r_upper_arm_link
+ r_upper_arm_roll_link
+ r_elbow_flex_link
+ r_forearm_link
+ r_forearm_roll_link
+ r_wrist_flex_link
+ r_wrist_roll_link
+ r_gripper_l_finger_link
+ r_gripper_l_finger_tip_link
+ r_gripper_r_finger_link
+ r_gripper_r_finger_tip_link
+ r_shoulder_pan_link
+ r_shoulder_lift_link" />
+
</node>
Modified: pkg/trunk/demos/2dnav_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/manifest.xml 2009-08-27 21:41:34 UTC (rev 23179)
+++ pkg/trunk/demos/2dnav_gazebo/manifest.xml 2009-08-27 21:43:37 UTC (rev 23180)
@@ -20,6 +20,8 @@
<depend package="point_cloud_assembler"/>
<depend package="semantic_point_annotator"/>
<depend package="or_robot_self_filter"/>
+ <depend package="robot_self_filter"/>
+ <depend package="3dnav_pr2"/>
<depend package="rviz"/>
<!-- Adding experimental controllers as a dependency b/c of tuckarm move -->
Modified: pkg/trunk/demos/milestone2/milestone2_actions/config/perception.xml
===================================================================
--- pkg/trunk/demos/milestone2/milestone2_actions/config/perception.xml 2009-08-27 21:41:34 UTC (rev 23179)
+++ pkg/trunk/demos/milestone2/milestone2_actions/config/perception.xml 2009-08-27 21:43:37 UTC (rev 23180)
@@ -1,4 +1,7 @@
<launch>
+
+ <include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
+
<include file="$(find pr2_alpha)/$(env ROBOT).machine" />
<node pkg="mux" type="throttle" args="3.0 base_scan base_scan_throttled" />
@@ -26,18 +29,126 @@
<rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
<rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="tilt_scan" />
- <param name="cloud_topic" value="tilt_scan_filtered" />
+ <param name="cloud_topic" value="tilt_scan_shadow_filtered" />
<param name="high_fidelity" value="true" />
</node>
+ <!-- Filter for tilt laser scans that hit the body of the robot -->
+ <node pkg="robot_self_filter" type="self_filter" name="tilt_laser_self_filter" respawn="true" output="screen">
+
+ <!-- The topic for the input cloud -->
+ <remap from="cloud_in" to="tilt_scan_shadow_filtered" />
+
+ <!-- The topic for the output cloud -->
+ <remap from="cloud_out" to="tilt_scan_filtered" />
+
+ <!-- The frame of the sensor used to obtain the data to be
+ filtered; This parameter is optional. If it is not specified,
+ shadow points will be considered outside -->
+ <param name="sensor_frame" type="string" value="laser_tilt_link" />
+
+ <!-- Minimum distance to sensor (for point not to be considered inside) -->
+ <param name="min_sensor_dist" type="double" value="0.01" />
+
+ <!-- The padding to be added for the body parts the robot can see -->
+ <param name="self_see_padd" type="double" value="0.01" />
+
+ <!-- The scaling to be added for the body parts the robot can see -->
+ <param name="self_see_scale" type="double" value="1.0" />
+
+ <!-- The names of the links the sensor can see -->
+ <param name="self_see_links" type="string" value="l_upper_arm_link
+ l_upper_arm_roll_link
+ l_elbow_flex_link
+ l_forearm_link
+ l_forearm_roll_link
+ l_wrist_flex_link
+ l_wrist_roll_link
+ l_gripper_l_finger_link
+ l_gripper_l_finger_tip_link
+ l_gripper_r_finger_link
+ l_gripper_r_finger_tip_link
+ l_shoulder_pan_link
+ l_shoulder_lift_link
+ r_upper_arm_link
+ r_upper_arm_roll_link
+ r_elbow_flex_link
+ r_forearm_link
+ r_forearm_roll_link
+ r_wrist_flex_link
+ r_wrist_roll_link
+ r_gripper_l_finger_link
+ r_gripper_l_finger_tip_link
+ r_gripper_r_finger_link
+ r_gripper_r_finger_tip_link
+ r_shoulder_pan_link
+ r_shoulder_lift_link
+ base_laser
+ base_link" />
+
+ </node>
+
<!-- Filter for base laser shadowing/veiling -->
<node pkg="laser_scan" type="scan_to_cloud" respawn="true" machine="three" name="base_shadow_filter" >
<rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
<rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="base_scan" />
- <param name="cloud_topic" value="base_scan_marking" />
+ <param name="cloud_topic" value="base_scan_shadow_filtered" />
</node>
+ <!-- Filter for base laser scans that hit the body of the robot -->
+ <node pkg="robot_self_filter" type="self_filter" name="base_laser_self_filter" respawn="true" output="screen">
+
+ <!-- The topic for the input cloud -->
+ <remap from="cloud_in" to="base_scan_shadow_filtered" />
+
+ <!-- The topic for the output cloud -->
+ <remap from="cloud_out" to="base_scan_marking" />
+
+ <!-- The frame of the sensor used to obtain the data to be
+ filtered; This parameter is optional. If it is not specified,
+ shadow points will be considered outside -->
+ <param name="sensor_frame" type="string" value="base_laser" />
+
+ <!-- Minimum distance to sensor (for point not to be considered inside) -->
+ <param name="min_sensor_dist" type="double" value="0.01" />
+
+ <!-- The padding to be added for the body parts the robot can see -->
+ <param name="self_see_padd" type="double" value="0.01" />
+
+ <!-- The scaling to be added for the body parts the robot can see -->
+ <param name="self_see_scale" type="double" value="1.0" />
+
+ <!-- The names of the links the sensor can see -->
+ <param name="self_see_links" type="string" value="l_upper_arm_link
+ l_upper_arm_roll_link
+ l_elbow_flex_link
+ l_forearm_link
+ l_forearm_roll_link
+ l_wrist_flex_link
+ l_wrist_roll_link
+ l_gripper_l_finger_link
+ l_gripper_l_finger_tip_link
+ l_gripper_r_finger_link
+ l_gripper_r_finger_tip_link
+ l_shoulder_pan_link
+ l_shoulder_lift_link
+ r_upper_arm_link
+ r_upper_arm_roll_link
+ r_elbow_flex_link
+ r_forearm_link
+ r_forearm_roll_link
+ r_wrist_flex_link
+ r_wrist_roll_link
+ r_gripper_l_finger_link
+ r_gripper_l_finger_tip_link
+ r_gripper_r_finger_link
+ r_gripper_r_finger_tip_link
+ r_shoulder_pan_link
+ r_shoulder_lift_link" />
+
+ </node>
+
<!-- Laser scan assembler for tilt laser -->
<node pkg="point_cloud_assembler" type="laser_scan_assembler_srv" name="laser_scan_assembler" respawn="true">
<remap from="scan_in" to="tilt_scan"/>
Modified: pkg/trunk/demos/milestone2/milestone2_actions/manifest.xml
===================================================================
--- pkg/trunk/demos/milestone2/milestone2_actions/manifest.xml 2009-08-27 21:41:34 UTC (rev 23179)
+++ pkg/trunk/demos/milestone2/milestone2_actions/manifest.xml 2009-08-27 21:43:37 UTC (rev 23180)
@@ -16,4 +16,6 @@
<depend package="pr2_experimental_controllers"/>
<depend package="switch_controller_translator"/>
<depend package="mux"/>
+ <depend package="robot_self_filter"/>
+ <depend package="3dnav_pr2"/>
</package>
Modified: pkg/trunk/sandbox/3dnav_pr2/launch/pr2_planning_environment.launch
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/launch/pr2_planning_environment.launch 2009-08-27 21:41:34 UTC (rev 23179)
+++ pkg/trunk/sandbox/3dnav_pr2/launch/pr2_planning_environment.launch 2009-08-27 21:43:37 UTC (rev 23180)
@@ -1,7 +1,7 @@
<launch>
<!-- send parameters for collision checking for PR2; this includes parameters for the self filter -->
- <rosparam command="load" ns="robot_description_collision" file="$(find 3dnav_pr2)/params/collision/collision_checks_right_arm.yaml" />
+ <rosparam command="load" ns="robot_description_collision" file="$(find 3dnav_pr2)/params/collision/collision_checks_both_arms.yaml" />
<!-- send parameters needed for motion planning -->
<rosparam command="load" ns="robot_description_planning" file="$(find 3dnav_pr2)/params/planning/planning.yaml" />
Modified: pkg/trunk/stacks/pr2/pr2_alpha/pre.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/pre.launch 2009-08-27 21:41:34 UTC (rev 23179)
+++ pkg/trunk/stacks/pr2/pr2_alpha/pre.launch 2009-08-27 21:43:37 UTC (rev 23180)
@@ -14,7 +14,7 @@
<!-- Power Board Control Node -->
<param name="power_board_serial" value="1021"/>
- <node machine="two" pkg="pr2_power_board" type="power_node" respawn="true"/>
+ <node machine="two" pkg="pr2_power_board" type="power_node" name="power_node" respawn="true"/>
<!-- Robot state publisher -->
<node machine="two" pkg="robot_state_publisher" type="state_publisher" name="robot_state_publisher">
@@ -23,7 +23,7 @@
</node>
<!-- Battery Monitor -->
- <node machine="two" pkg="ocean_battery_driver" type="ocean_server" respawn="true">
+ <node machine="two" pkg="ocean_battery_driver" name="ocean_server" type="ocean_server" respawn="true">
<param name="number_of_ports" type="int" value="4" />
<param name="port0" type="string" value="/dev/ttyUSB0" />
<param name="port1" type="string" value="/dev/ttyUSB1" />
@@ -32,7 +32,7 @@
<param name="debug_level" type="int" value="0" />
</node>
- <node pkg="power_monitor" type="power_monitor" respawn="true"/>
+ <node pkg="power_monitor" type="power_monitor" name="power_monitor" respawn="true"/>
<!-- Base Laser -->
@@ -60,7 +60,7 @@
<param name="imu/frameid" type="string" value="imu" />
<param name="imu/autocalibrate" type="bool" value="true" />
<param name="imu/angular_velocity_stdev" type="double" value="0.00017" />
- <node machine="realtime" pkg="imu_node" type="imu_node" output="screen"/>
+ <node machine="realtime" pkg="imu_node" type="imu_node" name="imu_node" output="screen"/>
<!-- Forearm Cameras -->
<node machine="two" name="forearm_cam_r" pkg="forearm_cam" type="forearm_node" respawn="false" output="screen">
@@ -93,26 +93,26 @@
<!-- Sound
- <node pkg="sound_play" type="soundplay_node.py" machine="three" />
+ <node pkg="sound_play" type="soundplay_node.py" name="soundplay_node" machine="three" />
-->
<!-- Runtime Diagnostics Logging -->
- <node pkg="rosrecord" type="rosrecord" args="-f /hwlog/pre_runtime_automatic /diagnostics" />
+ <node pkg="rosrecord" type="rosrecord" name="rosrecord_diagnostics" args="-f /hwlog/pre_runtime_automatic /diagnostics" />
<!-- NTP monitoring script Warns to console if sync error -->
- <node pkg="pr2_computer_monitor" type="ntp_monitor.py" args="pre2" machine="realtime"/>
- <node pkg="pr2_computer_monitor" type="ntp_monitor.py" args="fw1 7000" machine="two"/>
+ <node pkg="pr2_computer_monitor" name="realtime_ntp_monitor" type="ntp_monitor.py" args="pre2" machine="realtime"/>
+ <node pkg="pr2_computer_monitor" name="two_ntp_monitor" type="ntp_monitor.py" args="fw1 7000" machine="two"/>
<!-- Disk usage monitoring script Warns to console if disk full -->
- <node pkg="pr2_computer_monitor" type="hd_monitor.py" args="$(optenv HOME /home)" machine="realtime"/>
- <node pkg="pr2_computer_monitor" type="hd_monitor.py" args="$(optenv HOME /home)" machine="two"/>
+ <node pkg="pr2_computer_monitor" name="realtime_hd_monitor" type="hd_monitor.py" args="$(optenv HOME /home)" machine="realtime"/>
+ <node pkg="pr2_computer_monitor" name="two_hd_monitor" type="hd_monitor.py" args="$(optenv HOME /home)" machine="two"/>
<!-- Monitor CPU temp, usage -->
- <node pkg="pr2_computer_monitor" type="cpu_monitor.py" machine="realtime" />
- <node pkg="pr2_computer_monitor" type="cpu_monitor.py" machine="two" />
+ <node pkg="pr2_computer_monitor" name="realtime_cpu_monitor" type="cpu_monitor.py" machine="realtime" />
+ <node pkg="pr2_computer_monitor" name="two_cpu_monitor" type="cpu_monitor.py" machine="two" />
<!-- Joint states diagnostics logging -->
- <node pkg="mechanism_control" type="joints_to_diagnostics.py" machine="realtime" />
+ <node pkg="mechanism_control" name="joint_state_logging" type="joints_to_diagnostics.py" machine="realtime" />
<!-- Diagnostics aggregation -->
<node pkg="diagnostic_aggregator" type="aggregator_node"
Modified: pkg/trunk/stacks/pr2/pr2_alpha/pre.machine
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/pre.machine 2009-08-27 21:41:34 UTC (rev 23179)
+++ pkg/trunk/stacks/pr2/pr2_alpha/pre.machine 2009-08-27 21:43:37 UTC (rev 23180)
@@ -5,6 +5,8 @@
<machine name="realtime" address="pre1" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="true"/>
<machine name="two" address="pre2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+ <machine name="three" address="pre1" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+ <machine name="four" address="pre2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
<machine name="stereo" address="pre2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
</launch>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|