00001
00002
00003 """
00004 ArbotiX Node: serial connection to an ArbotiX board w/ PyPose/NUKE/ROS
00005 Copyright (c) 2008-2011 Michael E. Ferguson. All right reserved.
00006
00007 Redistribution and use in source and binary forms, with or without
00008 modification, are permitted provided that the following conditions are met:
00009 * Redistributions of source code must retain the above copyright
00010 notice, this list of conditions and the following disclaimer.
00011 * Redistributions in binary form must reproduce the above copyright
00012 notice, this list of conditions and the following disclaimer in the
00013 documentation and/or other materials provided with the distribution.
00014 * Neither the name of Vanadium Labs LLC nor the names of its
00015 contributors may be used to endorse or promote products derived
00016 from this software without specific prior written permission.
00017
00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00019 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 DISCLAIMED. IN NO EVENT SHALL VANADIUM LABS BE LIABLE FOR ANY DIRECT, INDIRECT,
00022 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00023 LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
00024 OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00025 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00026 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00027 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 """
00029
00030 import roslib; roslib.load_manifest('arbotix_python')
00031 import rospy
00032
00033 from arbotix_msgs.msg import *
00034 from arbotix_msgs.srv import *
00035
00036 from arbotix_python.arbotix import ArbotiX
00037 from arbotix_python.diff_controller import DiffController
00038 from arbotix_python.follow_controller import FollowController
00039 from arbotix_python.publishers import *
00040 from arbotix_python.servos import *
00041 from arbotix_python.io import *
00042
00043
00044
00045 class ArbotixROS(ArbotiX):
00046
00047 def __init__(self):
00048 pause = False
00049
00050
00051 port = rospy.get_param("~port", "/dev/ttyUSB0")
00052 baud = int(rospy.get_param("~baud", "115200"))
00053
00054 self.rate = rospy.get_param("~rate", 100.0)
00055 self.fake = rospy.get_param("~sim", False)
00056
00057 self.use_sync_read = rospy.get_param("~sync_read",True)
00058 self.use_sync_write = rospy.get_param("~sync_write",True)
00059
00060
00061 self.diagnostics = DiagnosticsPublisher()
00062 self.joint_state_publisher = JointStatePublisher()
00063
00064
00065 if not self.fake:
00066 ArbotiX.__init__(self, port, baud)
00067 rospy.sleep(1.0)
00068 rospy.loginfo("Started ArbotiX connection on port " + port + ".")
00069 else:
00070 rospy.loginfo("ArbotiX being simulated.")
00071
00072
00073 self.servos = Servos(self)
00074
00075
00076 self.controllers = list()
00077 controllers = rospy.get_param("~controllers", dict())
00078 for name, params in controllers.items():
00079 if params["type"] == "follow_controller":
00080 self.controllers.append(FollowController(self, name))
00081 if self.controllers[-1].onboard:
00082 pause = True
00083 elif params["type"] == "diff_controller":
00084 self.controllers.append(DiffController(self, name))
00085 pause = True
00086
00087
00088
00089 else:
00090 rospy.logerr("Unrecognized controller: " + params["type"])
00091
00092
00093 if not self.fake:
00094 if rospy.has_param("~digital_servos") or rospy.has_param("~digital_sensors") or rospy.has_param("~analog_sensors"):
00095 pause = True
00096 if pause:
00097 while self.getDigital(1) == -1:
00098 rospy.loginfo("Waiting for response...")
00099 rospy.sleep(0.25)
00100 rospy.loginfo("ArbotiX connected.")
00101
00102 for controller in self.controllers:
00103 controller.startup()
00104
00105
00106 rospy.Service('~SetupAnalogIn',SetupChannel, self.analogInCb)
00107 rospy.Service('~SetupDigitalIn',SetupChannel, self.digitalInCb)
00108 rospy.Service('~SetupDigitalOut',SetupChannel, self.digitalOutCb)
00109
00110 self.io = dict()
00111 if not self.fake:
00112 for v,t in {"digital_servos":DigitalServo,"digital_sensors":DigitalSensor,"analog_sensors":AnalogSensor}.items():
00113 temp = rospy.get_param("~"+v,dict())
00114 for name in temp.keys():
00115 pin = rospy.get_param('~'+v+'/'+name+'/pin',1)
00116 value = rospy.get_param('~'+v+'/'+name+'/value',0)
00117 rate = rospy.get_param('~'+v+'/'+name+'/rate',10)
00118 self.io[name] = t(name, pin, value, rate, self)
00119
00120 r = rospy.Rate(self.rate)
00121
00122
00123 while not rospy.is_shutdown():
00124
00125
00126 for controller in self.controllers:
00127 controller.update()
00128
00129
00130 self.servos.update(self.use_sync_write)
00131
00132
00133 for io in self.io.values():
00134 io.update()
00135
00136
00137 self.servos.interpolate(self.use_sync_read)
00138 self.joint_state_publisher.update(self.servos, self.controllers)
00139 self.diagnostics.update(self.servos, self.controllers)
00140
00141 r.sleep()
00142
00143
00144 for controller in self.controllers:
00145 controller.shutdown()
00146
00147
00148 def analogInCb(self, req):
00149
00150 if not self.fake:
00151 self.io[req.topic_name] = AnalogSensor(req.topic_name, req.pin, req.value, req.rate, self)
00152 return SetupChannelResponse()
00153
00154 def digitalInCb(self, req):
00155 if not self.fake:
00156 self.io[req.topic_name] = DigitalSensor(req.topic_name, req.pin, req.value, req.rate, self)
00157 return SetupChannelResponse()
00158
00159 def digitalOutCb(self, req):
00160 if not self.fake:
00161 self.io[req.topic_name] = DigitalServo(req.topic_name, req.pin, req.value, req.rate, self)
00162 return SetupChannelResponse()
00163
00164
00165 if __name__ == "__main__":
00166 rospy.init_node('arbotix')
00167 a = ArbotixROS()
00168