00001
00002
00003 """
00004 A ROS Node for the Arduino microcontroller
00005
00006 Created for the Pi Robot Project: http://www.pirobot.org
00007 Copyright (c) 2012 Patrick Goebel. All rights reserved.
00008
00009 This program is free software; you can redistribute it and/or modify
00010 it under the terms of the GNU General Public License as published by
00011 the Free Software Foundation; either version 2 of the License, or
00012 (at your option) any later version.
00013
00014 This program is distributed in the hope that it will be useful,
00015 but WITHOUT ANY WARRANTY; without even the implied warranty of
00016 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
00017 GNU General Public License for more details at:
00018
00019 http://www.gnu.org/licenses/gpl.html
00020 """
00021
00022 import roslib; roslib.load_manifest('ros_arduino_python')
00023 import rospy
00024 from arduino_driver import Arduino
00025 from arduino_sensors import *
00026 from ros_arduino_msgs.srv import *
00027 from base_controller import BaseController
00028 from geometry_msgs.msg import Twist
00029 import os, time
00030 import thread
00031
00032 class ArduinoROS():
00033 def __init__(self):
00034 rospy.init_node('Arduino', log_level=rospy.DEBUG)
00035
00036
00037 rospy.on_shutdown(self.shutdown)
00038
00039 self.port = rospy.get_param("~port", "/dev/ttyACM0")
00040 self.baud = int(rospy.get_param("~baud", 57600))
00041 self.timeout = rospy.get_param("~timeout", 0.5)
00042
00043
00044 self.rate = int(rospy.get_param("~rate", 50))
00045 r = rospy.Rate(self.rate)
00046
00047
00048
00049 self.sensorstate_rate = int(rospy.get_param("~sensorstate_rate", 10))
00050
00051 self.use_base_controller = rospy.get_param("~use_base_controller", False)
00052
00053
00054 now = rospy.Time.now()
00055 self.t_delta_sensors = rospy.Duration(1.0 / self.sensorstate_rate)
00056 self.t_next_sensors = now + self.t_delta_sensors
00057
00058
00059 self.cmd_vel = Twist()
00060
00061
00062 self.cmd_vel_pub = rospy.Publisher('cmd_vel', Twist)
00063
00064
00065
00066 self.sensorStatePub = rospy.Publisher('~sensor_state', SensorState)
00067
00068
00069 rospy.Service('~servo_write', ServoWrite, self.ServoWriteHandler)
00070
00071
00072 rospy.Service('~servo_read', ServoRead, self.ServoReadHandler)
00073
00074
00075 rospy.Service('~digital_set_direction', DigitalSetDirection, self.DigitalSetDirectionHandler)
00076
00077
00078 rospy.Service('~digital_write', DigitalWrite, self.DigitalWriteHandler)
00079
00080
00081 self.controller = Arduino(self.port, self.baud, self.timeout)
00082
00083
00084 self.controller.connect()
00085
00086 rospy.loginfo("Connected to Arduino on port " + self.port + " at " + str(self.baud) + " baud")
00087
00088
00089 mutex = thread.allocate_lock()
00090
00091
00092 self.mySensors = list()
00093
00094 sensor_params = rospy.get_param("~sensors", dict({}))
00095
00096 for name, params in sensor_params.iteritems():
00097
00098 try:
00099 params['direction']
00100 except:
00101 params['direction'] = 'input'
00102
00103 if params['type'] == "Ping":
00104 sensor = Ping(self.controller, name, params['pin'], params['rate'])
00105 elif params['type'] == "GP2D12":
00106 sensor = GP2D12(self.controller, name, params['pin'], params['rate'])
00107 elif params['type'] == 'Digital':
00108 sensor = DigitalSensor(self.controller, name, params['pin'], params['rate'], direction=params['direction'])
00109 elif params['type'] == 'Analog':
00110 sensor = AnalogSensor(self.controller, name, params['pin'], params['rate'], direction=params['direction'])
00111 elif params['type'] == 'PololuMotorCurrent':
00112 sensor = PololuMotorCurrent(self.controller, name, params['pin'], params['rate'])
00113 elif params['type'] == 'PhidgetsVoltage':
00114 sensor = PhidgetsVoltage(self.controller, name, params['pin'], params['rate'])
00115 elif params['type'] == 'PhidgetsCurrent':
00116 sensor = PhidgetsCurrent(self.controller, name, params['pin'], params['rate'])
00117
00118
00119
00120
00121
00122 self.mySensors.append(sensor)
00123 rospy.loginfo(name + " " + str(params))
00124
00125
00126 if self.use_base_controller:
00127 self.myBaseController = BaseController(self.controller)
00128
00129
00130 while not rospy.is_shutdown():
00131 for sensor in self.mySensors:
00132 mutex.acquire()
00133 sensor.poll()
00134 mutex.release()
00135
00136 if self.use_base_controller:
00137 mutex.acquire()
00138 self.myBaseController.poll()
00139 mutex.release()
00140
00141
00142 now = rospy.Time.now()
00143
00144 if now > self.t_next_sensors:
00145 msg = SensorState()
00146 msg.header.frame_id = 'base_link'
00147 msg.header.stamp = now
00148 for i in range(len(self.mySensors)):
00149 msg.name.append(self.mySensors[i].name)
00150 msg.value.append(self.mySensors[i].value)
00151 try:
00152 self.sensorStatePub.publish(msg)
00153 except:
00154 pass
00155
00156 self.t_next_sensors = now + self.t_delta_sensors
00157
00158 r.sleep()
00159
00160
00161 def ServoWriteHandler(self, req):
00162 self.controller.servo_write(req.id, req.value)
00163 return ServoWriteResponse()
00164
00165 def ServoReadHandler(self, req):
00166 self.controller.servo_read(req.id)
00167 return ServoReadResponse()
00168
00169 def DigitalSetDirectionHandler(self, req):
00170 self.controller.pin_mode(req.pin, req.direction)
00171 return DigitalSetDirectionResponse()
00172
00173 def DigitalWriteHandler(self, req):
00174 self.controller.digital_write(req.pin, req.value)
00175 return DigitalWriteResponse()
00176
00177 def shutdown(self):
00178
00179 try:
00180 rospy.loginfo("Stopping the robot...")
00181 self.cmd_vel_pub.Publish(Twist())
00182 rospy.sleep(2)
00183 except:
00184 pass
00185 rospy.loginfo("Shutting down Arduino Node...")
00186
00187 if __name__ == '__main__':
00188 myArduino = ArduinoROS()