test_bumper.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2008, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of the Willow Garage nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 #
00034 
00035 ## Gazebo test bumper for a box
00036 
00037 PKG = 'gazebo_plugins'
00038 NAME = 'test_bumper'
00039 
00040 import math
00041 import roslib
00042 roslib.load_manifest(PKG)
00043 
00044 import sys, unittest
00045 import os, os.path, threading, time
00046 import rospy, rostest
00047 from nav_msgs.msg import *
00048 from geometry_msgs.msg import Pose
00049 from geometry_msgs.msg import Twist
00050 from geometry_msgs.msg import Wrench
00051 from geometry_msgs.msg import Vector3
00052 from gazebo_msgs.msg import ContactsState
00053 from gazebo_msgs.msg import ContactState
00054 
00055 class BumperTest(unittest.TestCase):
00056     def __init__(self, *args):
00057         super(BumperTest, self).__init__(*args)
00058         self.success = False
00059 
00060         self.sample_count = 0
00061 
00062         self.min_samples_topic     = "~min_samples"
00063         self.min_samples     = 1000
00064 
00065         # in seconds
00066         self.test_duration_topic = "~test_duration"
00067         self.test_duration = 10.0
00068 
00069         # test start time in seconds
00070         self.test_start_time_topic = "~test_start_time"
00071         self.test_start_time = 0.0
00072 
00073         self.bumper_topic_name = "~bumper_topic_name"
00074         self.bumper_topic = "/test_bumper"
00075         self.bumper_state = ContactsState()
00076 
00077         self.fz_sum = 0
00078         self.fz_avg = 0
00079 
00080     def bumperStateInput(self, contacts_state):
00081         self.bumper_state = contacts_state
00082         self.sample_count+=1
00083         self.fz_sum += contacts_state.states[0].total_wrench.force.z
00084         self.fz_avg = self.fz_sum / self.sample_count
00085 
00086     def checkContact(self):
00087         # see if total wrench is close to 98.1N
00088         if self.sample_count > 20:
00089           if abs(self.fz_avg - 98.1) < 0.01:
00090             print "z force ",self.fz_avg
00091             self.success = True
00092         
00093 
00094     def test_bumper(self):
00095         print "LNK\n"
00096         rospy.init_node(NAME, anonymous=True)
00097         self.bumper_topic = rospy.get_param(self.bumper_topic_name,self.bumper_topic);
00098         self.min_samples = rospy.get_param(self.min_samples_topic,self.min_samples);
00099         self.test_duration = rospy.get_param(self.test_duration_topic,self.test_duration);
00100         self.test_start_time = rospy.get_param(self.test_start_time_topic,self.test_start_time);
00101 
00102         while not rospy.is_shutdown() and time.time() < self.test_start_time:
00103             rospy.stdinfo("Waiting for test to start at time [%s]"% self.test_start_time)
00104             time.sleep(0.1)
00105 
00106         print "subscribe"
00107         rospy.Subscriber(self.bumper_topic, ContactsState, self.bumperStateInput)
00108 
00109         start_t = time.time()
00110         timeout_t = start_t + self.test_duration
00111         while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
00112             self.checkContact()
00113             time.sleep(0.1)
00114         self.assert_(self.success)
00115         
00116 if __name__ == '__main__':
00117     print "Waiting for test to start at time "
00118     rostest.run(PKG, sys.argv[0], BumperTest, sys.argv) #, text_mode=True)
00119 
00120 


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Jun 6 2019 18:41:09