$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2010, 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 Willow Garage, Inc. 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 00036 import roslib; roslib.load_manifest('nxt_ros') 00037 import nxt.locator 00038 import rospy 00039 import math 00040 from nxt.motor import PORT_A, PORT_B, PORT_C 00041 from nxt.sensor import PORT_1, PORT_2, PORT_3, PORT_4 00042 from nxt.sensor import Type 00043 import nxt.sensor 00044 import nxt.motor 00045 import thread 00046 from sensor_msgs.msg import JointState, Imu 00047 from std_msgs.msg import Bool 00048 from nxt_msgs.msg import Range, Contact, JointCommand, Color, Gyro, Accelerometer 00049 from PyKDL import Rotation 00050 00051 POWER_TO_NM = 0.01 00052 POWER_MAX = 125 00053 00054 global my_lock 00055 my_lock = thread.allocate_lock() 00056 00057 def check_params(ns, params): 00058 for p in params: 00059 if not rospy.get_param(ns+'/'+p): 00060 return False 00061 return True 00062 00063 00064 # base class for sensors 00065 class Device: 00066 def __init__(self, params): 00067 self.desired_period = 1.0 / params['desired_frequency'] 00068 self.period = self.desired_period 00069 self.initialized = False 00070 self.name = params['name'] 00071 00072 def needs_trigger(self): 00073 # initialize 00074 if not self.initialized: 00075 self.initialized = True 00076 self.last_run = rospy.Time.now() 00077 rospy.logdebug('Initializing %s'%self.name) 00078 return False 00079 # compute frequency 00080 now = rospy.Time.now() 00081 period = 0.9 * self.period + 0.1 * (now - self.last_run).to_sec() 00082 00083 # check period 00084 if period > self.desired_period * 1.2: 00085 rospy.logwarn("%s not reaching desired frequency: actual %f, desired %f"%(self.name, 1.0/period, 1.0/self.desired_period)) 00086 elif period > self.desired_period * 1.5: 00087 rospy.logerr("%s not reaching desired frequency: actual %f, desired %f"%(self.name, 1.0/period, 1.0/self.desired_period)) 00088 00089 return period > self.desired_period 00090 00091 00092 def do_trigger(self): 00093 try: 00094 rospy.logdebug('Trigger %s with current frequency %f'%(self.name, 1.0/self.period)) 00095 now = rospy.Time.now() 00096 self.period = 0.9 * self.period + 0.1 * (now - self.last_run).to_sec() 00097 self.last_run = now 00098 self.trigger() 00099 rospy.logdebug('Trigger %s took %f mili-seconds'%(self.name, (rospy.Time.now() - now).to_sec()*1000)) 00100 except nxt.error.DirProtError: 00101 rospy.logwarn("caught an exception nxt.error.DirProtError") 00102 pass 00103 except nxt.error.I2CError: 00104 rospy.logwarn("caught an exception nxt.error.I2CError") 00105 pass 00106 00107 00108 class Motor(Device): 00109 def __init__(self, params, comm): 00110 Device.__init__(self, params) 00111 # create motor 00112 self.name = params['name'] 00113 self.motor = nxt.motor.Motor(comm, eval(params['port'])) 00114 self.cmd = 0 #default command 00115 00116 # create publisher 00117 self.pub = rospy.Publisher('joint_state', JointState) 00118 self.last_js = None 00119 00120 # create subscriber 00121 self.sub = rospy.Subscriber('joint_command', JointCommand, self.cmd_cb, None, 2) 00122 00123 00124 def cmd_cb(self, msg): 00125 if msg.name == self.name: 00126 00127 cmd = msg.effort / POWER_TO_NM 00128 if cmd > POWER_MAX: 00129 cmd = POWER_MAX 00130 elif cmd < -POWER_MAX: 00131 cmd = -POWER_MAX 00132 self.cmd = cmd #save command 00133 00134 def trigger(self): 00135 js = JointState() 00136 js.header.stamp = rospy.Time.now() 00137 state = self.motor.get_output_state() 00138 js.name.append(self.name) 00139 js.position.append(state[9] * math.pi / 180.0) 00140 js.effort.append(state[1] * POWER_TO_NM) 00141 vel = 0 00142 if self.last_js: 00143 vel = (js.position[0]-self.last_js.position[0])/(js.header.stamp-self.last_js.header.stamp).to_sec() 00144 js.velocity.append(vel) 00145 else: 00146 vel = 0 00147 js.velocity.append(vel) 00148 self.pub.publish(js) 00149 self.last_js = js 00150 00151 # send command 00152 self.motor.run(int(self.cmd), 0) 00153 00154 00155 00156 00157 class TouchSensor(Device): 00158 def __init__(self, params, comm): 00159 Device.__init__(self, params) 00160 # create touch sensor 00161 self.touch = nxt.sensor.TouchSensor(comm, eval(params['port'])) 00162 self.frame_id = params['frame_id'] 00163 00164 # create publisher 00165 self.pub = rospy.Publisher(params['name'], Contact) 00166 00167 def trigger(self): 00168 ct = Contact() 00169 ct.contact = self.touch.get_sample() 00170 ct.header.frame_id = self.frame_id 00171 ct.header.stamp = rospy.Time.now() 00172 self.pub.publish(ct) 00173 00174 00175 00176 class UltraSonicSensor(Device): 00177 def __init__(self, params, comm): 00178 Device.__init__(self, params) 00179 # create ultrasonic sensor 00180 self.ultrasonic = nxt.sensor.UltrasonicSensor(comm, eval(params['port'])) 00181 self.frame_id = params['frame_id'] 00182 self.spread = params['spread_angle'] 00183 self.min_range = params['min_range'] 00184 self.max_range = params['max_range'] 00185 00186 # create publisher 00187 self.pub = rospy.Publisher(params['name'], Range) 00188 00189 def trigger(self): 00190 ds = Range() 00191 ds.header.frame_id = self.frame_id 00192 ds.header.stamp = rospy.Time.now() 00193 ds.range = self.ultrasonic.get_sample()/100.0 00194 ds.spread_angle = self.spread 00195 ds.range_min = self.min_range 00196 ds.range_max = self.max_range 00197 self.pub.publish(ds) 00198 00199 00200 class GyroSensor(Device): 00201 def __init__(self, params, comm): 00202 Device.__init__(self, params) 00203 #create gyro sensor 00204 self.gyro = nxt.sensor.GyroSensor(comm, eval(params['port'])) 00205 self.frame_id = params['frame_id'] 00206 self.orientation = 0.0 00207 self.offset = 0.0 00208 self.prev_time = rospy.Time.now() 00209 00210 # calibrate 00211 rospy.loginfo("Calibrating Gyro. Don't move the robot now") 00212 start_time = rospy.Time.now() 00213 cal_duration = rospy.Duration(2.0) 00214 offset = 0 00215 tmp_time = rospy.Time.now() 00216 while rospy.Time.now() < start_time + cal_duration: 00217 rospy.sleep(0.01) 00218 sample = self.gyro.get_sample() 00219 now = rospy.Time.now() 00220 offset += (sample * (now - tmp_time).to_sec()) 00221 tmp_time = now 00222 self.offset = offset / (tmp_time - start_time).to_sec() 00223 rospy.loginfo("Gyro calibrated with offset %f"%self.offset) 00224 00225 # create publisher 00226 self.pub = rospy.Publisher(params['name'], Gyro) 00227 00228 # create publisher 00229 self.pub2 = rospy.Publisher(params['name']+"_imu", Imu) 00230 00231 def trigger(self): 00232 sample = self.gyro.get_sample() 00233 gs = Gyro() 00234 gs.header.frame_id = self.frame_id 00235 gs.header.stamp = rospy.Time.now() 00236 gs.calibration_offset.x = 0.0 00237 gs.calibration_offset.y = 0.0 00238 gs.calibration_offset.z = self.offset 00239 gs.angular_velocity.x = 0.0 00240 gs.angular_velocity.y = 0.0 00241 gs.angular_velocity.z = (sample-self.offset)*math.pi/180.0 00242 gs.angular_velocity_covariance = [0, 0, 0, 0, 0, 0, 0, 0, 1] 00243 self.pub.publish(gs) 00244 00245 imu = Imu() 00246 imu.header.frame_id = self.frame_id 00247 imu.header.stamp = rospy.Time.now() 00248 imu.angular_velocity.x = 0.0 00249 imu.angular_velocity.y = 0.0 00250 imu.angular_velocity.z = (sample-self.offset)*math.pi/180.0 00251 imu.angular_velocity_covariance = [0, 0, 0, 0, 0, 0, 0, 0, 1] 00252 imu.orientation_covariance = [0.001, 0, 0, 0, 0.001, 0, 0, 0, 0.1] 00253 self.orientation += imu.angular_velocity.z * (imu.header.stamp - self.prev_time).to_sec() 00254 self.prev_time = imu.header.stamp 00255 (imu.orientation.x, imu.orientation.y, imu.orientation.z, imu.orientation.w) = Rotation.RotZ(self.orientation).GetQuaternion() 00256 self.pub2.publish(imu) 00257 00258 class AccelerometerSensor(Device): 00259 def __init__(self, params, comm): 00260 Device.__init__(self, params) 00261 #create gyro sensor 00262 self.accel = nxt.sensor.AccelerometerSensor(comm, eval(params['port'])) 00263 self.frame_id = params['frame_id'] 00264 00265 # create publisher 00266 self.pub = rospy.Publisher(params['name'], Accelerometer) 00267 00268 def trigger(self): 00269 gs = Accelerometer() 00270 gs.header.frame_id = self.frame_id 00271 gs.header.stamp = rospy.Time.now() 00272 x,y,z = self.accel.get_sample() 00273 gs.linear_acceleration.x = x*9.8 00274 gs.linear_acceleration.y = y*9.8 00275 gs.linear_acceleration.z = z*9.8 00276 gs.linear_acceleration_covariance = [1, 0, 0, 0, 1, 0, 0, 0, 1] 00277 self.pub.publish(gs) 00278 00279 class ColorSensor(Device): 00280 def __init__(self, params, comm): 00281 Device.__init__(self, params) 00282 # create color sensor 00283 self.color = nxt.sensor.ColorSensor(comm, eval(params['port'])) 00284 self.frame_id = params['frame_id'] 00285 00286 # create publisher 00287 self.pub = rospy.Publisher(params['name'], Color) 00288 00289 def trigger(self): 00290 co = Color() 00291 co.header.frame_id = self.frame_id 00292 co.header.stamp = rospy.Time.now() 00293 co.intensity = 0.0 00294 color = self.color.get_color() 00295 if color == 1: # black 00296 co.r = 0.0 00297 co.g = 0.0 00298 co.b = 0.0 00299 elif color == 2: # blue 00300 co.r = 0.0 00301 co.g = 0.0 00302 co.b = 1.0 00303 elif color == 3: # green 00304 co.r = 0.0 00305 co.g = 1.0 00306 co.b = 0.0 00307 elif color == 4: # yellow 00308 co.r = 1.0 00309 co.g = 1.0 00310 co.b = 0.0 00311 elif color == 5: # red 00312 co.r = 1.0 00313 co.g = 0.0 00314 co.b = 1.0 00315 elif color == 6: # white 00316 co.r = 1.0 00317 co.g = 1.0 00318 co.b = 1.0 00319 else: 00320 rospy.logerr('Undefined color of color sensor') 00321 self.pub.publish(co) 00322 00323 00324 class IntensitySensor(Device): 00325 def __init__(self, params, comm): 00326 Device.__init__(self, params) 00327 # create intensity sensor 00328 self.intensity = nxt.sensor.ColorSensor(comm, eval(params['port'])) 00329 self.frame_id = params['frame_id'] 00330 self.color_r = params['color_r'] 00331 self.color_g = params['color_g'] 00332 self.color_b = params['color_b'] 00333 00334 if self.color_r == 1.0 and self.color_g == 0.0 and self.color_b == 0.0: 00335 self.color = 'red' 00336 elif self.color_r == 0.0 and self.color_g == 1.0 and self.color_b == 0.0: 00337 self.color = 'green' 00338 elif self.color_r == 0.0 and self.color_g == 0.0 and self.color_b == 1.0: 00339 self.color = 'blue' 00340 elif self.color_r == 0.0 and self.color_g == 0.0 and self.color_b == 0.0: 00341 self.color = 'off' 00342 else: 00343 rospy.logerr('Invalid RGB values specifies for intensity color sensor') 00344 00345 # create publisher 00346 self.pub = rospy.Publisher(params['name'], Color) 00347 00348 def trigger(self): 00349 co = Color() 00350 co.header.frame_id = self.frame_id 00351 co.header.stamp = rospy.Time.now() 00352 co.r = self.color_r 00353 co.g = self.color_g 00354 co.b = self.color_b 00355 co.intensity = self.intensity.get_reflected_light(self.color) 00356 self.pub.publish(co) 00357 00358 00359 00360 def main(): 00361 rospy.init_node('nxt_ros') 00362 ns = 'nxt_robot' 00363 host = rospy.get_param("~host", None) 00364 sock = nxt.locator.find_one_brick(host) 00365 b = sock.connect() 00366 00367 config = rospy.get_param("~"+ns) 00368 components = [] 00369 for c in config: 00370 rospy.loginfo("Creating %s with name %s on %s",c['type'],c['name'],c['port']) 00371 if c['type'] == 'motor': 00372 components.append(Motor(c, b)) 00373 elif c['type'] == 'touch': 00374 components.append(TouchSensor(c, b)) 00375 elif c['type'] == 'ultrasonic': 00376 components.append(UltraSonicSensor(c, b)) 00377 elif c['type'] == 'color': 00378 components.append(ColorSensor(c, b)) 00379 elif c['type'] == 'intensity': 00380 components.append(IntensitySensor(c, b)) 00381 elif c['type'] == 'gyro': 00382 components.append(GyroSensor(c, b)) 00383 elif c['type'] == 'accelerometer': 00384 components.append(AccelerometerSensor(c, b)) 00385 else: 00386 rospy.logerr('Invalid sensor/actuator type %s'%c['type']) 00387 00388 callback_handle_frequency = 10.0 00389 last_callback_handle = rospy.Time.now() 00390 while not rospy.is_shutdown(): 00391 my_lock.acquire() 00392 triggered = False 00393 for c in components: 00394 if c.needs_trigger() and not triggered: 00395 c.do_trigger() 00396 triggered = True 00397 my_lock.release() 00398 now = rospy.Time.now() 00399 if (now - last_callback_handle).to_sec() > 1.0/callback_handle_frequency: 00400 last_callback_handle = now 00401 rospy.sleep(0.01) 00402 00403 00404 00405 if __name__ == '__main__': 00406 main()