00001
00002
00003 """
00004 follow_controller.py - controller for a kinematic chain
00005 Copyright (c) 2011 Vanadium Labs LLC. 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 rospy, actionlib
00031 from control_msgs.msg import FollowJointTrajectoryAction
00032 from diagnostic_msgs.msg import *
00033
00034 from ax12 import *
00035
00036 class FollowController:
00037 """ A controller for joint chains, exposing a FollowJointTrajectory action. """
00038
00039 def __init__(self, device, name):
00040 self.name = name
00041 self.device = device
00042 self.fake = device.fake
00043 self.interpolating = 0
00044
00045
00046 self.rate = rospy.get_param('~controllers/'+name+'/rate',50.0)
00047 self.joints = rospy.get_param('~controllers/'+name+'/joints')
00048 self.index = rospy.get_param('~controllers/'+name+'/index', len(device.controllers))
00049 self.onboard = rospy.get_param('~controllers/'+name+'/onboard', True)
00050 if self.fake:
00051 self.onboard = False
00052 for joint in self.joints:
00053 self.device.servos[joint].controller = self
00054 self.ids = [self.device.servos[joint].id for joint in self.joints]
00055
00056
00057 self.joint_names = []
00058 self.joint_positions = []
00059 self.joint_velocities = []
00060
00061
00062 name = rospy.get_param('~controllers/'+name+'/action_name','follow_joint_trajectory')
00063 self.server = actionlib.SimpleActionServer(name, FollowJointTrajectoryAction, execute_cb=self.actionCb, auto_start=False)
00064
00065 rospy.loginfo("Started FollowController ("+self.name+"). Joints: " + str(self.joints) + " on C" + str(self.index))
00066
00067 def startup(self):
00068 if not self.fake:
00069 self.setup()
00070 self.server.start()
00071
00072 def update(self):
00073 self.status()
00074
00075 def shutdown(self):
00076 pass
00077
00078 def actionCb(self, goal):
00079 rospy.loginfo(self.name + ": Action goal recieved.")
00080 traj = goal.trajectory
00081
00082 if set(self.joints) != set(traj.joint_names):
00083 msg = "Trajectory joint names does not match action controlled joints." + str(traj.joint_names)
00084 rospy.logerr(msg)
00085 self.server.set_aborted(text=msg)
00086 return
00087
00088 if not traj.points:
00089 msg = "Trajectory empy."
00090 rospy.logerr(msg)
00091 self.server.set_aborted(text=msg)
00092 return
00093
00094 try:
00095 indexes = [traj.joint_names.index(joint) for joint in self.joints]
00096 except ValueError as val:
00097 msg = "Trajectory invalid."
00098 rospy.logerr(msg)
00099 self.server.set_aborted(text=msg)
00100 return
00101
00102
00103 time = rospy.Time.now()
00104 start = traj.header.stamp
00105 r = rospy.Rate(self.rate)
00106 last = [ self.device.servos[joint].angle for joint in self.joints ]
00107 for point in traj.points:
00108 while rospy.Time.now() + rospy.Duration(0.01) < start:
00109 rospy.sleep(0.01)
00110 if self.onboard:
00111 while self.interpolating > 0:
00112 rospy.sleep(0.01)
00113 positions = [ self.device.servos[self.joints[k]].setControl(point.positions[indexes[k]]) for k in range(len(indexes)) ]
00114 t = ((start + point.time_from_start) - rospy.Time.now()).to_sec()
00115 if t < 1/30.0:
00116 continue
00117 rospy.logdebug(self.name + ": Sending Point," + str(positions) + " " + str(t))
00118 self.write(positions, t)
00119 self.interpolating = 1
00120 else:
00121 desired = [ point.positions[k] for k in indexes ]
00122 endtime = start + point.time_from_start
00123 while rospy.Time.now() + rospy.Duration(0.01) < endtime:
00124 err = [ (d-c) for d,c in zip(desired,last) ]
00125 velocity = [ abs(x / (self.rate * (endtime - rospy.Time.now()).to_sec())) for x in err ]
00126 rospy.logdebug(err)
00127 for i in range(len(self.joints)):
00128 if err[i] > 0.01 or err[i] < -0.01:
00129 cmd = err[i]
00130 top = velocity[i]
00131 if cmd > top:
00132 cmd = top
00133 elif cmd < -top:
00134 cmd = -top
00135 last[i] += cmd
00136 self.device.servos[self.joints[i]].dirty = True
00137 self.device.servos[self.joints[i]].relaxed = False
00138 self.device.servos[self.joints[i]].desired = last[i]
00139 else:
00140 velocity[i] = 0
00141 r.sleep()
00142
00143 while self.onboard and self.interpolating != 0:
00144 rospy.sleep(0.01)
00145
00146 rospy.loginfo(self.name + ": Done.")
00147 self.server.set_succeeded()
00148
00149 def active(self):
00150 """ Is controller overriding servo internal control? """
00151 return self.onboard and self.server.is_active()
00152
00153 def getDiagnostics(self):
00154 """ Get a diagnostics status. """
00155 msg = DiagnosticStatus()
00156 msg.name = self.name
00157 msg.level = DiagnosticStatus.OK
00158 msg.message = "OK"
00159 if self.server.is_active():
00160 msg.values.append(KeyValue("State", "Active"))
00161 else:
00162 msg.values.append(KeyValue("State", "Not Active"))
00163 return msg
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175 def setup(self):
00176 params = [self.index] + self.ids
00177 success = self.device.execute(253, AX_CONTROL_SETUP, params)
00178
00179 def write(self, positions, time):
00180 """ Write a movement to occur in time (s). """
00181 self.interpolating = 1
00182 params = [self.index]
00183 for p in positions:
00184 params.append( int(p)%256 )
00185 params.append( (int(p)>>8)%256 )
00186 params.append(int(time*30)%256)
00187 success = self.device.execute(253, AX_CONTROL_WRITE, params)
00188
00189 def status(self):
00190 if self.onboard and self.interpolating != 0:
00191 try:
00192 self.interpolating = self.device.execute(253, AX_CONTROL_STAT, [self.index])[0]
00193 except:
00194 pass
00195