set_wrench.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 send wrench topic for gazebo_ros_force consumption
00036 
00037 PKG = 'gazebo_plugins'
00038 NAME = 'set_wrench'
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 
00048 from geometry_msgs.msg import Wrench, Vector3
00049 import tf.transformations as tft
00050 from numpy import float64
00051 
00052 class SimIfaceControl():
00053   def __init__(self):
00054     self.update_rate=10
00055     self.target_l = [0,0,0] # linear
00056     self.target_e = [0,0,0] # angular
00057     self.topic_name = "set_wrench_topic"
00058     self.timeout=1
00059     rospy.init_node(NAME, anonymous=True)
00060 
00061   def setWrench(self):
00062     # get goal from commandline
00063     for i in range(0,len(sys.argv)):
00064       if sys.argv[i] == '-update_rate':
00065         if len(sys.argv) > i+1:
00066           self.update_rate = float(sys.argv[i+1])
00067       if sys.argv[i] == '-timeout':
00068         if len(sys.argv) > i+1:
00069           self.timeout = float(sys.argv[i+1])
00070       if sys.argv[i] == '-x':
00071         if len(sys.argv) > i+1:
00072           self.target_l[0] = float(sys.argv[i+1])
00073       if sys.argv[i] == '-y':
00074         if len(sys.argv) > i+1:
00075           self.target_l[1] = float(sys.argv[i+1])
00076       if sys.argv[i] == '-z':
00077         if len(sys.argv) > i+1:
00078           self.target_l[2] = float(sys.argv[i+1])
00079       if sys.argv[i] == '-R':
00080         if len(sys.argv) > i+1:
00081           self.target_e[0] = float(sys.argv[i+1])
00082       if sys.argv[i] == '-P':
00083         if len(sys.argv) > i+1:
00084           self.target_e[1] = float(sys.argv[i+1])
00085       if sys.argv[i] == '-Y':
00086         if len(sys.argv) > i+1:
00087           self.target_e[2] = float(sys.argv[i+1])
00088       if sys.argv[i] == '-t':
00089         if len(sys.argv) > i+1:
00090           self.topic_name = sys.argv[i+1]
00091 
00092     # setup rospy
00093     self.pub_set_wrench_topic = rospy.Publisher(self.topic_name, Wrench)
00094 
00095     # compoose goal message
00096     w = Wrench(Vector3(self.target_l[0],self.target_l[1],self.target_l[2]),Vector3(self.target_e[0],self.target_e[1],self.target_e[2]))
00097 
00098     # publish topic if specified
00099     timeout_t = time.time() + self.timeout
00100     while not rospy.is_shutdown() and time.time() < timeout_t:
00101       # publish target wrench
00102       self.pub_set_wrench_topic.publish(w)
00103 
00104       if self.update_rate > 0:
00105         time.sleep(1.0/self.update_rate)
00106       else:
00107         time.sleep(0.001)
00108 
00109 def print_usage(exit_code = 0):
00110     print '''Commands:
00111     -update_rate <Hz> - update rate, default to 10 Hz
00112     -timeout <seconds> - test timeout in seconds. default to 1 seconds
00113     -x <x in meters>
00114     -y <y in meters>
00115     -z <z in meters>
00116     -R <roll in radians>
00117     -P <pitch in radians>
00118     -Y <yaw in radians>
00119     -t set wrench topic name
00120 '''
00121 
00122 if __name__ == '__main__':
00123     #print usage if not arguments
00124     if len(sys.argv) == 1:
00125       print_usage()
00126     else:
00127       sic = SimIfaceControl()
00128       sic.setWrench()
00129 
00130 
00131 


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