|
From: <wa...@us...> - 2009-03-10 05:38:25
|
Revision: 12332
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=12332&view=rev
Author: wattsk
Date: 2009-03-10 04:36:01 +0000 (Tue, 10 Mar 2009)
Log Message:
-----------
Head and hokuyo impact tests updates
Modified Paths:
--------------
pkg/trunk/hardware_test/self_test/src/selftest_example.cpp
pkg/trunk/prcore/robot_msgs/msg/TestData.msg
Added Paths:
-----------
pkg/trunk/hardware_test/life_test/head_test/head_impact_test/
pkg/trunk/hardware_test/life_test/head_test/head_impact_test/cal.xml
pkg/trunk/hardware_test/life_test/head_test/head_impact_test/head.xml
pkg/trunk/hardware_test/life_test/head_test/head_impact_test/head_defs_without_limits.xml
pkg/trunk/hardware_test/life_test/head_test/head_impact_test/impact_head_test.py
pkg/trunk/hardware_test/life_test/head_test/head_impact_test/init.launch
pkg/trunk/hardware_test/life_test/head_test/head_impact_test/init.machine
pkg/trunk/hardware_test/life_test/head_test/head_impact_test/manifest.xml
pkg/trunk/hardware_test/life_test/head_test/head_impact_test/run_test.launch
pkg/trunk/hardware_test/life_test/head_test/head_impact_test/send_description.launch
pkg/trunk/hardware_test/life_test/hokuyo_test/
pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/
pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/head.xml
pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/head_defs_without_limits.xml
pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/impact_hokuyo_test.py
pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/init.launch
pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/init.machine
pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/manifest.xml
pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/run_test.launch
pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/send_description.launch
Removed Paths:
-------------
pkg/trunk/controllers/qualification_controllers/dynamic_verification_controllers/.build_version
pkg/trunk/hardware_test/dynamic_verification/.build_version
pkg/trunk/hardware_test/life_test/head_test/impact_test/
Deleted: pkg/trunk/controllers/qualification_controllers/dynamic_verification_controllers/.build_version
===================================================================
--- pkg/trunk/controllers/qualification_controllers/dynamic_verification_controllers/.build_version 2009-03-10 04:33:58 UTC (rev 12331)
+++ pkg/trunk/controllers/qualification_controllers/dynamic_verification_controllers/.build_version 2009-03-10 04:36:01 UTC (rev 12332)
@@ -1 +0,0 @@
-https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/trunk/controllers/qualification_controllers/dynamic_verification_controllers:12201
Deleted: pkg/trunk/hardware_test/dynamic_verification/.build_version
===================================================================
--- pkg/trunk/hardware_test/dynamic_verification/.build_version 2009-03-10 04:33:58 UTC (rev 12331)
+++ pkg/trunk/hardware_test/dynamic_verification/.build_version 2009-03-10 04:36:01 UTC (rev 12332)
@@ -1 +0,0 @@
-:
Added: pkg/trunk/hardware_test/life_test/head_test/head_impact_test/cal.xml
===================================================================
--- pkg/trunk/hardware_test/life_test/head_test/head_impact_test/cal.xml (rev 0)
+++ pkg/trunk/hardware_test/life_test/head_test/head_impact_test/cal.xml 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,5 @@
+<controllers>
+ <include filename="$(find head_impact_test)/head_defs_without_limits.xml" />
+ <head_calibrator />
+ <tilting_laser_calibrator name="laser_tilt" />
+</controllers>
Added: pkg/trunk/hardware_test/life_test/head_test/head_impact_test/head.xml
===================================================================
--- pkg/trunk/hardware_test/life_test/head_test/head_impact_test/head.xml (rev 0)
+++ pkg/trunk/hardware_test/life_test/head_test/head_impact_test/head.xml 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,17 @@
+<?xml version="1.0"?>
+<robot name="test_head">
+ <include filename="head_defs_without_limits.xml" />
+
+<pr2_head_pan name="head_pan" parent="world">
+ <origin xyz="0 0 0.3815" rpy="0 0 0" />
+</pr2_head_pan>
+
+<pr2_head_tilt name="head_tilt" parent="head_pan">
+ <origin xyz="0.058 0 0" rpy="0 0 0" />
+</pr2_head_tilt>
+
+<pr2_tilting_laser name="laser_tilt" parent="world">
+ <origin xyz="0 0 0.03" rpy="0 0 0" />
+</pr2_tilting_laser>
+
+</robot>
Added: pkg/trunk/hardware_test/life_test/head_test/head_impact_test/head_defs_without_limits.xml
===================================================================
--- pkg/trunk/hardware_test/life_test/head_test/head_impact_test/head_defs_without_limits.xml (rev 0)
+++ pkg/trunk/hardware_test/life_test/head_test/head_impact_test/head_defs_without_limits.xml 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,361 @@
+<?xml version="1.0"?>
+
+<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
+ xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
+ xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
+
+ <property name="M_PI" value="3.1415926535897931" />
+
+ <macro name="pr2_tilting_laser" params="name parent *origin">
+
+ <joint name="${name}_mount_joint" type="revolute">
+ <axis xyz="0 1 0" />
+ <anchor xyz="0 0 0" />
+ <!-- Removed max, min limits -->
+ <limit effort="0.5292" velocity="100"
+ k_position="100" k_velocity="0.05"
+ safety_length_min="0.15" safety_length_max="0.15" />
+ <calibration reference_position="-0.35" values="0 0" />
+ <joint_properties damping="1.0" />
+ </joint>
+
+ <link name="${name}_mount_link">
+ <parent name="${parent}" />
+ <insert_block name="origin" />
+ <joint name="${name}_mount_joint" />
+ <inertial>
+ <mass value="0.1" />
+ <com xyz="0 0 0" />
+ <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <map name="gazebo_material" flag="gazebo">
+ <elem key="material">Gazebo/PioneerBody</elem>
+ </map>
+ <geometry name="${name}_mount_visual">
+ <mesh filename="hok_tilt" />
+ </geometry>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry name="${name}_mount_collision" >
+ <box size=".001 .001 .001" />
+ </geometry>
+ </collision>
+ </link>
+
+ <transmission type="SimpleTransmission" name="${name}_mount_trans">
+ <actuator name="${name}_mount_motor" />
+ <joint name="${name}_mount_joint" />
+ <mechanicalReduction>6.0</mechanicalReduction>
+ </transmission>
+
+ <joint name="${name}_joint" type="fixed">
+ <axis xyz="0 1 0" />
+ <anchor xyz="0 0 0" />
+ </joint>
+
+ <sensor name="${name}_link" type="laser">
+ <parent name="${name}_mount_link" />
+ <origin xyz="0 0 0.03" rpy="0 0 0" />
+ <joint name="${name}_joint" />
+ <inertial>
+ <mass value="0.1" />
+ <com xyz="0 0 0" />
+ <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry name="${name}_visual">
+ <mesh scale="0.001 0.001 0.001" />
+ </geometry>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry name="${name}_collision" >
+ <box size=".001 .001 .001" />
+ </geometry>
+ </collision>
+
+ <map name="sensor" flag="gazebo">
+ <verbatim key="sensor_${name}_ray">
+ <sensor:ray name="${name}">
+ <rayCount>640</rayCount>
+ <rangeCount>640</rangeCount>
+ <laserCount>1</laserCount>
+
+ <origin>0.0 0.0 0.0</origin>
+ <displayRays>false</displayRays>
+
+ <minAngle>-80</minAngle>
+ <maxAngle> 80</maxAngle>
+
+ <minRange>0.05</minRange>
+ <maxRange>10.0</maxRange>
+ <updateRate>20.0</updateRate>
+ <controller:ros_laser name="ros_${name}_controller" plugin="libros_laser.so">
+ <gaussianNoise>0.005</gaussianNoise>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>20.0</updateRate>
+ <topicName>tilt_scan</topicName>
+ <frameName>${name}_link</frameName>
+ <interface:laser name="ros_${name}_iface" />
+ </controller:ros_laser>
+ </sensor:ray>
+ </verbatim>
+ </map>
+
+ </sensor>
+
+ </macro>
+
+
+ <property name="stereo_size_x" value="0.005" />
+ <property name="stereo_size_y" value="0.010" />
+ <property name="stereo_size_z" value="0.005" />
+ <property name="stereo_center_box_center_offset_x" value="0.00" />
+ <property name="stereo_center_box_center_offset_z" value="0.05" />
+
+ <macro name="stereo_camera" params="name parent *origin">
+ <joint name="${name}_joint" type="fixed" />
+
+ <sensor name="${name}_link" type="camera">
+ <parent name="${parent}" />
+ <insert_block name="origin" />
+ <joint name="${name}_joint" />
+
+ <inertial>
+ <mass value="0.1" />
+ <com xyz="0 0 0" />
+ <inertia ixx="0.00482611007" ixy="-0.000144683999" ixz="0.000110076136"
+ iyy="0.005218991412" iyz="-0.000314239509" izz="0.008618784925" />
+ </inertial>
+
+ <visual>
+ <origin xyz="${stereo_center_box_center_offset_x} 0 ${stereo_center_box_center_offset_z}" rpy="0 0 0" />
+ <map name="gazebo_material" flag="gazebo">
+ <elem key="material">Gazebo/Blue</elem>
+ </map>
+ <geometry name="${name}_visual">
+ <mesh scale="${stereo_size_x} ${stereo_size_y} ${stereo_size_z}" />
+ </geometry>
+ </visual>
+
+ <collision>
+ <origin xyz="${stereo_center_box_center_offset_x} 0 ${stereo_center_box_center_offset_z}" rpy="0 0 0" />
+ <geometry name="${name}_collision">
+ <box size="${stereo_size_x} ${stereo_size_y} ${stereo_size_z}" />
+ </geometry>
+ </collision>
+
+
+ <map name="sensor" flag="gazebo">
+ <verbatim key="sensor_${name}_camera">
+ <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}_l_controller" plugin="libros_camera.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>20.0</updateRate>
+ <topicName>${name}_l/image</topicName>
+ <frameName>${name}_link</frameName>
+ <interface:camera name="${name}_l_iface" />
+ </controller:ros_camera>
+ </sensor:camera>
+ </verbatim>
+ </map>
+ <map name="sensor" flag="gazebo">
+ <verbatim key="sensor_${name}_ray">
+ <sensor:ray name="${name}_laser">
+ <rayCount>10</rayCount>
+ <rangeCount>10</rangeCount>
+ <laserCount>1</laserCount>
+
+ <origin>0.0 0.0 0.05</origin>
+ <displayRays>false</displayRays>
+
+ <minAngle>-15</minAngle>
+ <maxAngle> 15</maxAngle>
+
+ <minRange>0.05</minRange>
+ <maxRange>100.0</maxRange>
+ <updateRate>10.0</updateRate>
+
+ <verticalRayCount>10</verticalRayCount>
+ <verticalRangeCount>10</verticalRangeCount>
+ <verticalMinAngle>-20</verticalMinAngle>
+ <verticalMaxAngle> 0</verticalMaxAngle>
+
+ <controller:ros_block_laser name="${name}_laser_controller" plugin="libros_block_laser.so">
+ <gaussianNoise>0.005</gaussianNoise>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>10.0</updateRate>
+ <topicName>full_cloud</topicName>
+ <frameName>${name}_link</frameName>
+ <interface:laser name="${name}_laser_iface" />
+ </controller:ros_block_laser>
+ </sensor:ray>
+ </verbatim>
+ </map>
+ </sensor>
+ </macro>
+
+
+ <macro name="pr2_head_pan" params="name parent *origin">
+
+ <joint name="${name}_joint" type="revolute">
+ <axis xyz="0 0 1" />
+ <!-- Removed max, min limits -->
+ <limit effort="2.645"
+ velocity="100" k_velocity="1.5"
+ safety_length_min="0.15" safety_length_max="0.15" k_position="100" />
+ <calibration reference_position="-2.79" values="0 0" />
+ <joint_properties damping="1.0" />
+ </joint>
+
+ <transmission type="SimpleTransmission" name="${name}_trans">
+ <actuator name="${name}_motor" />
+ <joint name="${name}_joint" />
+ <mechanicalReduction>6.0</mechanicalReduction>
+ </transmission>
+
+ <link name="${name}_link">
+ <parent name="${parent}" />
+ <insert_block name="origin" />
+ <joint name="${name}_joint" />
+
+ <inertial>
+ <mass value="1.611118" />
+ <com xyz=" -0.005717 0.010312 -0.029649 " />
+ <inertia ixx="0.00482611007" ixy="-0.000144683999" ixz="0.000110076136"
+ iyy="0.005218991412" iyz="-0.000314239509" izz="0.008618784925" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0.0" rpy="0 0 0 " />
+ <map name="gazebo_material" flag="gazebo">
+ <elem key="material">Gazebo/Blue</elem>
+ </map>
+ <geometry name="${name}_visual">
+ <mesh filename="head_pan" />
+ </geometry>
+ </visual>
+
+ <collision>
+ <origin xyz=" 0 0 0" rpy="0.0 0.0 0.0 " />
+ <geometry name="${name}_collision">
+ <box size="0.188 0.219 0.137" />
+ </geometry>
+ </collision>
+
+ </link>
+ </macro>
+
+
+ <macro name="pr2_head_tilt" params="name parent *origin">
+
+ <joint name="${name}_joint" type="revolute">
+ <axis xyz="0 1 0" />
+ <!-- Safety limits on max, min removed -->
+ <limit effort="12.21"
+ velocity="100" k_velocity="1.5"
+ safety_length_min="0.1" safety_length_max="0.1" k_position="100" />
+ <calibration reference_position="-0.195" values="0 0" />
+ <joint_properties damping="1.0" />
+ </joint>
+
+ <transmission type="SimpleTransmission" name="${name}_trans">
+ <actuator name="${name}_motor" />
+ <joint name="${name}_joint" />
+ <mechanicalReduction>6.0</mechanicalReduction>
+ </transmission>
+
+ <link name="${name}_link">
+ <parent name="${parent}" />
+ <insert_block name="origin" />
+ <joint name="${name}_joint" />
+
+ <inertial>
+ <mass value="1.749727" />
+ <com xyz="0.041935 0.003569 0.028143" />
+ <inertia ixx="0.010602303435" ixy="-0.000408814235" ixz="0.00198303894" iyy="0.011874383747" iyz="0.000197908779" izz="0.005516790626" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0.0 0.0 0.0 " />
+ <map name="gazebo_material" flag="gazebo">
+ <elem key="material">Gazebo/Green</elem>
+ </map>
+ <geometry name="${name}_visual">
+ <mesh filename="head_tilt" />
+ </geometry>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0 " rpy="0 0 0" />
+ <geometry name="${name}_collision">
+ <box size="0.164 0.253 0.181" />
+ </geometry>
+ </collision>
+ </link>
+ </macro>
+
+
+ <macro name="pr2_head" params="name parent *origin">
+ <pr2_head_pan name="${name}_pan" parent="${parent}">
+ <insert_block name="origin" />
+ </pr2_head_pan>
+
+ <pr2_head_tilt name="${name}_tilt" parent="${name}_pan_link">
+ <origin xyz="0.058 0 0" rpy="0 0 0" />
+ </pr2_head_tilt>
+
+ <stereo_camera name="stereo" parent="${name}_tilt_link">
+ <origin xyz="0.0232 0 0.0645" rpy="0 0 0" />
+ </stereo_camera>
+ </macro>
+
+
+
+ <!-- Calibration -->
+
+ <macro name="head_calibrator">
+ <controller name="cal_head_pan" topic="cal_head_pan"
+ type="JointCalibrationControllerNode">
+ <calibrate joint="head_pan_joint"
+ actuator="head_pan_motor"
+ transmission="head_pan_trans"
+ velocity="-1.5" />
+ <pid p="2.0" i="0.0" d="0" iClamp="1.0" />
+ </controller>
+
+ <controller name="cal_head_tilt" topic="cal_head_tilt"
+ type="JointCalibrationControllerNode">
+ <calibrate joint="head_tilt_joint"
+ actuator="head_tilt_motor"
+ transmission="head_tilt_trans"
+ velocity="-0.7" />
+ <pid p="4.0" i="0.0" d="0" iClamp="5.0" />
+ </controller>
+ </macro>
+
+ <macro name="tilting_laser_calibrator" params="name">
+ <controller name="cal_${name}" topic="cal_${name}" type="JointCalibrationControllerNode">
+ <calibrate joint="${name}_mount_joint"
+ actuator="${name}_mount_motor"
+ transmission="${name}_mount_trans"
+ velocity="-1.5" />
+ <pid p=".3" i="0.1" d="0" iClamp="1.0" />
+ </controller>
+ </macro>
+
+</robot>
Added: pkg/trunk/hardware_test/life_test/head_test/head_impact_test/impact_head_test.py
===================================================================
--- pkg/trunk/hardware_test/life_test/head_test/head_impact_test/impact_head_test.py (rev 0)
+++ pkg/trunk/hardware_test/life_test/head_test/head_impact_test/impact_head_test.py 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,108 @@
+#! /usr/bin/python
+# Copyright (c) 2009, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in the
+# documentation and/or other materials provided with the distribution.
+# * Neither the name of the Willow Garage, Inc. nor the names of its
+# contributors may be used to endorse or promote products derived from
+# this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+
+# This script brings up an effort controller runs a 500x life test on the
+# head tilt joint, pan joint and laser tilt joint.
+#
+# Author: Kevin Watts
+
+##@package head_impact_test
+#
+# @mainpage
+# @htmlinclude manifest.xml
+#
+# @section usage Usage
+# @verbatim $ run_test.launch @endverbatim
+#
+# @par Description
+# @verbatim
+# This program runs a impact life test on the head tilt, pan and laser tilt. 500 cycles, with effort safety removed.
+# @endverbatim
+
+
+
+CONTROLLER_NAMES = ["head_tilt_effort", "head_pan_effort", "laser_tilt_effort"]
+JOINT_NAMES = ["head_tilt_joint", "head_pan_joint", "laser_tilt_mount_joint"]
+
+import sys
+
+import roslib
+roslib.load_manifest('head_impact_test') # Rename to path head_impact_test
+import rospy
+from std_msgs.msg import *
+from mechanism_control import mechanism
+from robot_srvs.srv import SpawnController, KillController
+from time import sleep
+
+## Create XML code for controller on the fly
+def xml_for(controller, joint):
+ return '''\
+<controller name=\"%s\" type=\"JointEffortControllerNode\">\
+<joint name=\"%s\" />\
+</controller>''' % (controller, joint)
+
+def main():
+ rospy.init_node('head_impact_test', anonymous=True)
+ for i in range(0,3):
+ joint = JOINT_NAMES[i]
+ controller = CONTROLLER_NAMES[i]
+ #print xml_for(controller,joint)
+
+ rospy.wait_for_service('spawn_controller')
+ spawn_controller = rospy.ServiceProxy('spawn_controller', SpawnController)
+ kill_controller = rospy.ServiceProxy('kill_controller', KillController)
+
+ resp = spawn_controller(xml_for(controller, joint))
+ if len(resp.ok) < 1 or not ord(resp.ok[0]):
+ print "Failed to spawn effort controller"
+ else:
+ print "Spawned controller %s successfully" % controller
+
+ pub = rospy.Publisher("/%s/set_command" % controller, Float64)
+
+ try:
+ for i in range(0,3):
+ if rospy.is_shutdown():
+ break
+ # Back and forth
+ sleep(1.5)
+ effort = -1000; # Min effort
+ pub.publish(Float64(effort))
+ sleep(1.5)
+ effort = 1000; # Max effort
+ pub.publish(Float64(effort))
+ finally:
+ kill_controller(controller)
+ sleep(5)
+ sys.exit(0)
+
+if __name__ == '__main__':
+ main()
+
+
+
Added: pkg/trunk/hardware_test/life_test/head_test/head_impact_test/init.launch
===================================================================
--- pkg/trunk/hardware_test/life_test/head_test/head_impact_test/init.launch (rev 0)
+++ pkg/trunk/hardware_test/life_test/head_test/head_impact_test/init.launch 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,22 @@
+<launch>
+ <include file="$(find head_impact_test)/init.machine" />
+ <include file="$(find head_impact_test)/send_description.launch" />
+
+ <!-- pr2_etherCAT -->
+ <node machine="xenomai_root" pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i eth0 -x /robotdesc/pr2"/>
+
+ <!-- Calibration -->
+ <!--node pkg="mechanism_bringup" type="calibrate.py"
+ args="$(find head_impact_test)/cal.xml"
+ output="screen" /-->
+
+ <!-- Power board -->
+ <!--node pkg="pr2_power_board" type="power_node" respawn="true"/ -->
+
+ <!-- Runtime Diagnostics Logging -->
+ <node pkg="rosrecord" type="rosrecord"
+ args="-f ~/impact_test.bag /diagnostics" />
+
+<!-- Controllers not brought up here, called in impact_head_test.py -->
+
+</launch>
Added: pkg/trunk/hardware_test/life_test/head_test/head_impact_test/init.machine
===================================================================
--- pkg/trunk/hardware_test/life_test/head_test/head_impact_test/init.machine (rev 0)
+++ pkg/trunk/hardware_test/life_test/head_test/head_impact_test/init.machine 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,6 @@
+<launch>
+ <machine name="xenomai_root" user="root" address="localhost"
+ ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="never"/>
+ <machine name="xenomai" address="localhost"
+ ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+</launch>
Added: pkg/trunk/hardware_test/life_test/head_test/head_impact_test/manifest.xml
===================================================================
--- pkg/trunk/hardware_test/life_test/head_test/head_impact_test/manifest.xml (rev 0)
+++ pkg/trunk/hardware_test/life_test/head_test/head_impact_test/manifest.xml 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,14 @@
+<package>
+
+ <description brief="Code and configuration for performing life testing on head tilt, pan and laser tilt.">
+ </description>
+ <author>Kevin Watts</author>
+ <license>BSD</license>
+ <review status="na" notes=""/>
+
+ <depend package="pr2_etherCAT" />
+ <depend package="pr2_power_board"/>
+ <depend package="rosrecord"/>
+ <depend package="pr2_mechanism_controllers"/>
+
+</package>
Added: pkg/trunk/hardware_test/life_test/head_test/head_impact_test/run_test.launch
===================================================================
--- pkg/trunk/hardware_test/life_test/head_test/head_impact_test/run_test.launch (rev 0)
+++ pkg/trunk/hardware_test/life_test/head_test/head_impact_test/run_test.launch 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,4 @@
+<launch>
+ <include file="$(find head_impact_test)/init.launch" />
+ <node pkg="head_impact_test" type="impact_head_test.py" />
+</launch>
Added: pkg/trunk/hardware_test/life_test/head_test/head_impact_test/send_description.launch
===================================================================
--- pkg/trunk/hardware_test/life_test/head_test/head_impact_test/send_description.launch (rev 0)
+++ pkg/trunk/hardware_test/life_test/head_test/head_impact_test/send_description.launch 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,6 @@
+<launch>
+
+ <param name="robotdesc/pr2"
+ command="$(find xacro)/xacro.py '$(find head_impact_test)/head.xml'" />
+
+</launch>
\ No newline at end of file
Added: pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/head.xml
===================================================================
--- pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/head.xml (rev 0)
+++ pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/head.xml 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,17 @@
+<?xml version="1.0"?>
+<robot name="test_head">
+ <include filename="head_defs_without_limits.xml" />
+
+<pr2_head_pan name="head_pan" parent="world">
+ <origin xyz="0 0 0.3815" rpy="0 0 0" />
+</pr2_head_pan>
+
+<pr2_head_tilt name="head_tilt" parent="head_pan">
+ <origin xyz="0.058 0 0" rpy="0 0 0" />
+</pr2_head_tilt>
+
+<pr2_tilting_laser name="laser_tilt" parent="world">
+ <origin xyz="0 0 0.03" rpy="0 0 0" />
+</pr2_tilting_laser>
+
+</robot>
Added: pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/head_defs_without_limits.xml
===================================================================
--- pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/head_defs_without_limits.xml (rev 0)
+++ pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/head_defs_without_limits.xml 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,361 @@
+<?xml version="1.0"?>
+
+<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
+ xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
+ xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
+
+ <property name="M_PI" value="3.1415926535897931" />
+
+ <macro name="pr2_tilting_laser" params="name parent *origin">
+
+ <joint name="${name}_mount_joint" type="revolute">
+ <axis xyz="0 1 0" />
+ <anchor xyz="0 0 0" />
+ <!-- Removed max, min limits -->
+ <limit effort="0.5292" velocity="100"
+ k_position="100" k_velocity="0.05"
+ safety_length_min="0.15" safety_length_max="0.15" />
+ <calibration reference_position="-0.35" values="0 0" />
+ <joint_properties damping="1.0" />
+ </joint>
+
+ <link name="${name}_mount_link">
+ <parent name="${parent}" />
+ <insert_block name="origin" />
+ <joint name="${name}_mount_joint" />
+ <inertial>
+ <mass value="0.1" />
+ <com xyz="0 0 0" />
+ <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <map name="gazebo_material" flag="gazebo">
+ <elem key="material">Gazebo/PioneerBody</elem>
+ </map>
+ <geometry name="${name}_mount_visual">
+ <mesh filename="hok_tilt" />
+ </geometry>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry name="${name}_mount_collision" >
+ <box size=".001 .001 .001" />
+ </geometry>
+ </collision>
+ </link>
+
+ <transmission type="SimpleTransmission" name="${name}_mount_trans">
+ <actuator name="${name}_mount_motor" />
+ <joint name="${name}_mount_joint" />
+ <mechanicalReduction>6.0</mechanicalReduction>
+ </transmission>
+
+ <joint name="${name}_joint" type="fixed">
+ <axis xyz="0 1 0" />
+ <anchor xyz="0 0 0" />
+ </joint>
+
+ <sensor name="${name}_link" type="laser">
+ <parent name="${name}_mount_link" />
+ <origin xyz="0 0 0.03" rpy="0 0 0" />
+ <joint name="${name}_joint" />
+ <inertial>
+ <mass value="0.1" />
+ <com xyz="0 0 0" />
+ <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry name="${name}_visual">
+ <mesh scale="0.001 0.001 0.001" />
+ </geometry>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry name="${name}_collision" >
+ <box size=".001 .001 .001" />
+ </geometry>
+ </collision>
+
+ <map name="sensor" flag="gazebo">
+ <verbatim key="sensor_${name}_ray">
+ <sensor:ray name="${name}">
+ <rayCount>640</rayCount>
+ <rangeCount>640</rangeCount>
+ <laserCount>1</laserCount>
+
+ <origin>0.0 0.0 0.0</origin>
+ <displayRays>false</displayRays>
+
+ <minAngle>-80</minAngle>
+ <maxAngle> 80</maxAngle>
+
+ <minRange>0.05</minRange>
+ <maxRange>10.0</maxRange>
+ <updateRate>20.0</updateRate>
+ <controller:ros_laser name="ros_${name}_controller" plugin="libros_laser.so">
+ <gaussianNoise>0.005</gaussianNoise>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>20.0</updateRate>
+ <topicName>tilt_scan</topicName>
+ <frameName>${name}_link</frameName>
+ <interface:laser name="ros_${name}_iface" />
+ </controller:ros_laser>
+ </sensor:ray>
+ </verbatim>
+ </map>
+
+ </sensor>
+
+ </macro>
+
+
+ <property name="stereo_size_x" value="0.005" />
+ <property name="stereo_size_y" value="0.010" />
+ <property name="stereo_size_z" value="0.005" />
+ <property name="stereo_center_box_center_offset_x" value="0.00" />
+ <property name="stereo_center_box_center_offset_z" value="0.05" />
+
+ <macro name="stereo_camera" params="name parent *origin">
+ <joint name="${name}_joint" type="fixed" />
+
+ <sensor name="${name}_link" type="camera">
+ <parent name="${parent}" />
+ <insert_block name="origin" />
+ <joint name="${name}_joint" />
+
+ <inertial>
+ <mass value="0.1" />
+ <com xyz="0 0 0" />
+ <inertia ixx="0.00482611007" ixy="-0.000144683999" ixz="0.000110076136"
+ iyy="0.005218991412" iyz="-0.000314239509" izz="0.008618784925" />
+ </inertial>
+
+ <visual>
+ <origin xyz="${stereo_center_box_center_offset_x} 0 ${stereo_center_box_center_offset_z}" rpy="0 0 0" />
+ <map name="gazebo_material" flag="gazebo">
+ <elem key="material">Gazebo/Blue</elem>
+ </map>
+ <geometry name="${name}_visual">
+ <mesh scale="${stereo_size_x} ${stereo_size_y} ${stereo_size_z}" />
+ </geometry>
+ </visual>
+
+ <collision>
+ <origin xyz="${stereo_center_box_center_offset_x} 0 ${stereo_center_box_center_offset_z}" rpy="0 0 0" />
+ <geometry name="${name}_collision">
+ <box size="${stereo_size_x} ${stereo_size_y} ${stereo_size_z}" />
+ </geometry>
+ </collision>
+
+
+ <map name="sensor" flag="gazebo">
+ <verbatim key="sensor_${name}_camera">
+ <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}_l_controller" plugin="libros_camera.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>20.0</updateRate>
+ <topicName>${name}_l/image</topicName>
+ <frameName>${name}_link</frameName>
+ <interface:camera name="${name}_l_iface" />
+ </controller:ros_camera>
+ </sensor:camera>
+ </verbatim>
+ </map>
+ <map name="sensor" flag="gazebo">
+ <verbatim key="sensor_${name}_ray">
+ <sensor:ray name="${name}_laser">
+ <rayCount>10</rayCount>
+ <rangeCount>10</rangeCount>
+ <laserCount>1</laserCount>
+
+ <origin>0.0 0.0 0.05</origin>
+ <displayRays>false</displayRays>
+
+ <minAngle>-15</minAngle>
+ <maxAngle> 15</maxAngle>
+
+ <minRange>0.05</minRange>
+ <maxRange>100.0</maxRange>
+ <updateRate>10.0</updateRate>
+
+ <verticalRayCount>10</verticalRayCount>
+ <verticalRangeCount>10</verticalRangeCount>
+ <verticalMinAngle>-20</verticalMinAngle>
+ <verticalMaxAngle> 0</verticalMaxAngle>
+
+ <controller:ros_block_laser name="${name}_laser_controller" plugin="libros_block_laser.so">
+ <gaussianNoise>0.005</gaussianNoise>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>10.0</updateRate>
+ <topicName>full_cloud</topicName>
+ <frameName>${name}_link</frameName>
+ <interface:laser name="${name}_laser_iface" />
+ </controller:ros_block_laser>
+ </sensor:ray>
+ </verbatim>
+ </map>
+ </sensor>
+ </macro>
+
+
+ <macro name="pr2_head_pan" params="name parent *origin">
+
+ <joint name="${name}_joint" type="revolute">
+ <axis xyz="0 0 1" />
+ <!-- Removed max, min limits -->
+ <limit effort="2.645"
+ velocity="100" k_velocity="1.5"
+ safety_length_min="0.15" safety_length_max="0.15" k_position="100" />
+ <calibration reference_position="-2.79" values="0 0" />
+ <joint_properties damping="1.0" />
+ </joint>
+
+ <transmission type="SimpleTransmission" name="${name}_trans">
+ <actuator name="${name}_motor" />
+ <joint name="${name}_joint" />
+ <mechanicalReduction>6.0</mechanicalReduction>
+ </transmission>
+
+ <link name="${name}_link">
+ <parent name="${parent}" />
+ <insert_block name="origin" />
+ <joint name="${name}_joint" />
+
+ <inertial>
+ <mass value="1.611118" />
+ <com xyz=" -0.005717 0.010312 -0.029649 " />
+ <inertia ixx="0.00482611007" ixy="-0.000144683999" ixz="0.000110076136"
+ iyy="0.005218991412" iyz="-0.000314239509" izz="0.008618784925" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0.0" rpy="0 0 0 " />
+ <map name="gazebo_material" flag="gazebo">
+ <elem key="material">Gazebo/Blue</elem>
+ </map>
+ <geometry name="${name}_visual">
+ <mesh filename="head_pan" />
+ </geometry>
+ </visual>
+
+ <collision>
+ <origin xyz=" 0 0 0" rpy="0.0 0.0 0.0 " />
+ <geometry name="${name}_collision">
+ <box size="0.188 0.219 0.137" />
+ </geometry>
+ </collision>
+
+ </link>
+ </macro>
+
+
+ <macro name="pr2_head_tilt" params="name parent *origin">
+
+ <joint name="${name}_joint" type="revolute">
+ <axis xyz="0 1 0" />
+ <!-- Safety limits on max, min removed -->
+ <limit effort="12.21"
+ velocity="100" k_velocity="1.5"
+ safety_length_min="0.1" safety_length_max="0.1" k_position="100" />
+ <calibration reference_position="-0.195" values="0 0" />
+ <joint_properties damping="1.0" />
+ </joint>
+
+ <transmission type="SimpleTransmission" name="${name}_trans">
+ <actuator name="${name}_motor" />
+ <joint name="${name}_joint" />
+ <mechanicalReduction>6.0</mechanicalReduction>
+ </transmission>
+
+ <link name="${name}_link">
+ <parent name="${parent}" />
+ <insert_block name="origin" />
+ <joint name="${name}_joint" />
+
+ <inertial>
+ <mass value="1.749727" />
+ <com xyz="0.041935 0.003569 0.028143" />
+ <inertia ixx="0.010602303435" ixy="-0.000408814235" ixz="0.00198303894" iyy="0.011874383747" iyz="0.000197908779" izz="0.005516790626" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0.0 0.0 0.0 " />
+ <map name="gazebo_material" flag="gazebo">
+ <elem key="material">Gazebo/Green</elem>
+ </map>
+ <geometry name="${name}_visual">
+ <mesh filename="head_tilt" />
+ </geometry>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0 " rpy="0 0 0" />
+ <geometry name="${name}_collision">
+ <box size="0.164 0.253 0.181" />
+ </geometry>
+ </collision>
+ </link>
+ </macro>
+
+
+ <macro name="pr2_head" params="name parent *origin">
+ <pr2_head_pan name="${name}_pan" parent="${parent}">
+ <insert_block name="origin" />
+ </pr2_head_pan>
+
+ <pr2_head_tilt name="${name}_tilt" parent="${name}_pan_link">
+ <origin xyz="0.058 0 0" rpy="0 0 0" />
+ </pr2_head_tilt>
+
+ <stereo_camera name="stereo" parent="${name}_tilt_link">
+ <origin xyz="0.0232 0 0.0645" rpy="0 0 0" />
+ </stereo_camera>
+ </macro>
+
+
+
+ <!-- Calibration -->
+
+ <macro name="head_calibrator">
+ <controller name="cal_head_pan" topic="cal_head_pan"
+ type="JointCalibrationControllerNode">
+ <calibrate joint="head_pan_joint"
+ actuator="head_pan_motor"
+ transmission="head_pan_trans"
+ velocity="-1.5" />
+ <pid p="2.0" i="0.0" d="0" iClamp="1.0" />
+ </controller>
+
+ <controller name="cal_head_tilt" topic="cal_head_tilt"
+ type="JointCalibrationControllerNode">
+ <calibrate joint="head_tilt_joint"
+ actuator="head_tilt_motor"
+ transmission="head_tilt_trans"
+ velocity="-0.7" />
+ <pid p="4.0" i="0.0" d="0" iClamp="5.0" />
+ </controller>
+ </macro>
+
+ <macro name="tilting_laser_calibrator" params="name">
+ <controller name="cal_${name}" topic="cal_${name}" type="JointCalibrationControllerNode">
+ <calibrate joint="${name}_mount_joint"
+ actuator="${name}_mount_motor"
+ transmission="${name}_mount_trans"
+ velocity="-1.5" />
+ <pid p=".3" i="0.1" d="0" iClamp="1.0" />
+ </controller>
+ </macro>
+
+</robot>
Added: pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/impact_hokuyo_test.py
===================================================================
--- pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/impact_hokuyo_test.py (rev 0)
+++ pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/impact_hokuyo_test.py 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,102 @@
+#! /usr/bin/python
+# Copyright (c) 2009, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in the
+# documentation and/or other materials provided with the distribution.
+# * Neither the name of the Willow Garage, Inc. nor the names of its
+# contributors may be used to endorse or promote products derived from
+# this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+
+# This script brings up an effort controller runs a 500x life test on the
+# head tilt joint, pan joint and laser tilt joint.
+#
+# Author: Kevin Watts
+
+##@package impact_test
+#
+# @mainpage
+# @htmlinclude manifest.xml
+#
+# @section usage Usage
+# @verbatim $ run_test.launch @endverbatim
+#
+# @par Description
+# @verbatim
+# This program runs a impact life test on the head tilt, pan and laser tilt. 500 cycles, with effort safety removed.
+# @endverbatim
+
+import sys
+
+import rostools
+rostools.update_path('hokuyo_impact_test')
+import rospy
+from std_msgs.msg import *
+from mechanism_control import mechanism
+from robot_srvs.srv import SpawnController, KillController
+from time import sleep
+
+## Create XML code for controller on the fly
+def xml_for(controller, joint):
+ return '''\
+<controller name=\"%s\" type=\"JointEffortControllerNode\">\
+<joint name=\"%s\" />\
+</controller>''' % (controller, joint)
+
+def main():
+ rospy.init_node('hokuyo_impact_test', anonymous=True)
+ joint = "laser_tilt_mount_joint"
+ controller = "laser_tilt_effort"
+ print xml_for(controller,joint)
+
+ rospy.wait_for_service('spawn_controller')
+ spawn_controller = rospy.ServiceProxy('spawn_controller', SpawnController)
+ kill_controller = rospy.ServiceProxy('kill_controller', KillController)
+
+ resp = spawn_controller(xml_for(controller, joint))
+ if len(resp.ok) < 1 or not ord(resp.ok[0]):
+ print "Failed to spawn effort controller"
+ else:
+ print "Spawned controller %s successfully" % controller
+
+ pub = rospy.Publisher("/%s/set_command" % controller, Float64)
+
+ try:
+ for i in range(1,5):
+ if rospy.is_shutdown():
+ break
+ # Back and forth
+ sleep(1.5)
+ effort = -1000; # Min effort
+ pub.publish(Float64(effort))
+ sleep(1.5)
+ effort = 1000; # Max effort
+ pub.publish(Float64(effort))
+ finally:
+ kill_controller(controller)
+ sleep(5)
+ sys.exit(0)
+
+if __name__ == '__main__':
+ main()
+
+
+
Added: pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/init.launch
===================================================================
--- pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/init.launch (rev 0)
+++ pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/init.launch 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,22 @@
+<launch>
+ <include file="$(find impact_test)/init.machine" />
+ <include file="$(find impact_test)/send_description.launch" />
+
+ <!-- pr2_etherCAT -->
+ <node machine="xenomai_root" pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i eth0 -x /robotdesc/pr2"/>
+
+ <!-- Calibration -->
+ <!--node pkg="mechanism_bringup" type="calibrate.py"
+ args="$(find hokuyo_impact_test)/cal.xml"
+ output="screen" /-->
+
+ <!-- Power board -->
+ <!--node pkg="pr2_power_board" type="power_node" respawn="true"/ -->
+
+ <!-- Runtime Diagnostics Logging -->
+ <node pkg="rosrecord" type="rosrecord"
+ args="-f ~/impact_test.bag /diagnostics" />
+
+<!-- Controllers not brought up here, called in impact_hokuyo_test.py -->
+
+</launch>
Added: pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/init.machine
===================================================================
--- pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/init.machine (rev 0)
+++ pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/init.machine 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,6 @@
+<launch>
+ <machine name="xenomai_root" user="root" address="localhost"
+ ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="never"/>
+ <machine name="xenomai" address="localhost"
+ ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+</launch>
Added: pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/manifest.xml
===================================================================
--- pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/manifest.xml (rev 0)
+++ pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/manifest.xml 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,14 @@
+<package>
+
+ <description brief="Code and configuration for performing impact testing on hokuyo laser tilt assembly">
+ </description>
+ <author>Kevin Watts</author>
+ <license>BSD</license>
+ <review status="na" notes=""/>
+
+ <depend package="pr2_etherCAT" />
+ <depend package="pr2_power_board"/>
+ <depend package="rosrecord"/>
+ <depend package="pr2_mechanism_controllers"/>
+
+</package>
Added: pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/run_test.launch
===================================================================
--- pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/run_test.launch (rev 0)
+++ pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/run_test.launch 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,4 @@
+<launch>
+ <include file="$(find hokuyo_impact_test)/init.launch" />
+ <node pkg="impact_test" type="impact_hokuyo_test.py" />
+</launch>
Added: pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/send_description.launch
===================================================================
--- pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/send_description.launch (rev 0)
+++ pkg/trunk/hardware_test/life_test/hokuyo_test/hokuyo_impact_test/send_description.launch 2009-03-10 04:36:01 UTC (rev 12332)
@@ -0,0 +1,6 @@
+<launch>
+
+ <param name="robotdesc/pr2"
+ command="$(find xacro)/xacro.py '$(find impact_test)/head.xml'" />
+
+</launch>
\ No newline at end of file
Modified: pkg/trunk/hardware_test/self_test/src/selftest_example.cpp
===================================================================
--- pkg/trunk/hardware_test/self_test/src/selftest_example.cpp 2009-03-10 04:33:58 UTC (rev 12331)
+++ pkg/trunk/hardware_test/self_test/src/selftest_example.cpp 2009-03-10 04:36:01 UTC (rev 12332)
@@ -36,7 +36,7 @@
#include <stdexcept>
-using namespace std;
+// using namespace std;
class MyNode : public ros::Node
{
Modified: pkg/trunk/prcore/robot_msgs/msg/TestData.msg
===================================================================
--- pkg/trunk/prcore/robot_msgs/msg/TestData.msg 2009-03-10 04:33:58 UTC (rev 12331)
+++ pkg/trunk/prcore/robot_msgs/msg/TestData.msg 2009-03-10 04:36:01 UTC (rev 12332)
@@ -1,4 +1,5 @@
string test_name
+string joint_name
float32[] time
float32[] cmd
float32[] effort
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|