set_wrench.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2008, Willow Garage, Inc.
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions
9 # are met:
10 #
11 # * Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above
14 # copyright notice, this list of conditions and the following
15 # disclaimer in the documentation and/or other materials provided
16 # with the distribution.
17 # * Neither the name of the Willow Garage nor the names of its
18 # contributors may be used to endorse or promote products derived
19 # from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 # POSSIBILITY OF SUCH DAMAGE.
33 #
34 
35 ## Gazebo send wrench topic for gazebo_ros_force consumption
36 
37 PKG = 'gazebo_plugins'
38 NAME = 'set_wrench'
39 
40 import math
41 import roslib
42 roslib.load_manifest(PKG)
43 
44 import sys, unittest
45 import os, os.path, threading, time
46 import rospy, rostest
47 
48 from geometry_msgs.msg import Wrench, Vector3
49 import tf.transformations as tft
50 from numpy import float64
51 
53  def __init__(self):
54  self.update_rate=10
55  self.target_l = [0,0,0] # linear
56  self.target_e = [0,0,0] # angular
57  self.topic_name = "set_wrench_topic"
58  self.timeout=1
59  rospy.init_node(NAME, anonymous=True)
60 
61  def setWrench(self):
62  # get goal from commandline
63  for i in range(0,len(sys.argv)):
64  if sys.argv[i] == '-update_rate':
65  if len(sys.argv) > i+1:
66  self.update_rate = float(sys.argv[i+1])
67  if sys.argv[i] == '-timeout':
68  if len(sys.argv) > i+1:
69  self.timeout = float(sys.argv[i+1])
70  if sys.argv[i] == '-x':
71  if len(sys.argv) > i+1:
72  self.target_l[0] = float(sys.argv[i+1])
73  if sys.argv[i] == '-y':
74  if len(sys.argv) > i+1:
75  self.target_l[1] = float(sys.argv[i+1])
76  if sys.argv[i] == '-z':
77  if len(sys.argv) > i+1:
78  self.target_l[2] = float(sys.argv[i+1])
79  if sys.argv[i] == '-R':
80  if len(sys.argv) > i+1:
81  self.target_e[0] = float(sys.argv[i+1])
82  if sys.argv[i] == '-P':
83  if len(sys.argv) > i+1:
84  self.target_e[1] = float(sys.argv[i+1])
85  if sys.argv[i] == '-Y':
86  if len(sys.argv) > i+1:
87  self.target_e[2] = float(sys.argv[i+1])
88  if sys.argv[i] == '-t':
89  if len(sys.argv) > i+1:
90  self.topic_name = sys.argv[i+1]
91 
92  # setup rospy
93  self.pub_set_wrench_topic = rospy.Publisher(self.topic_name, Wrench)
94 
95  # compoose goal message
96  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]))
97 
98  # publish topic if specified
99  timeout_t = time.time() + self.timeout
100  while not rospy.is_shutdown() and time.time() < timeout_t:
101  # publish target wrench
102  self.pub_set_wrench_topic.publish(w)
103 
104  if self.update_rate > 0:
105  time.sleep(1.0/self.update_rate)
106  else:
107  time.sleep(0.001)
108 
109 def print_usage(exit_code = 0):
110  print '''Commands:
111  -update_rate <Hz> - update rate, default to 10 Hz
112  -timeout <seconds> - test timeout in seconds. default to 1 seconds
113  -x <x in meters>
114  -y <y in meters>
115  -z <z in meters>
116  -R <roll in radians>
117  -P <pitch in radians>
118  -Y <yaw in radians>
119  -t set wrench topic name
120 '''
121 
122 if __name__ == '__main__':
123  #print usage if not arguments
124  if len(sys.argv) == 1:
125  print_usage()
126  else:
128  sic.setWrench()
129 
130 
131 
def print_usage(exit_code=0)
Definition: set_wrench.py:109


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Mar 26 2019 02:31:27