$search
00001 # -*- coding: utf-8 -*- 00002 # 00003 # Software License Agreement (BSD License) 00004 # 00005 # Copyright (c) 2010-2011, Antons Rebguns. 00006 # All rights reserved. 00007 # 00008 # Redistribution and use in source and binary forms, with or without 00009 # modification, are permitted provided that the following conditions 00010 # are met: 00011 # 00012 # * Redistributions of source code must retain the above copyright 00013 # notice, this list of conditions and the following disclaimer. 00014 # * Redistributions in binary form must reproduce the above 00015 # copyright notice, this list of conditions and the following 00016 # disclaimer in the documentation and/or other materials provided 00017 # with the distribution. 00018 # * Neither the name of University of Arizona nor the names of its 00019 # contributors may be used to endorse or promote products derived 00020 # from this software without specific prior written permission. 00021 # 00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 # POSSIBILITY OF SUCH DAMAGE. 00034 00035 from __future__ import division 00036 00037 00038 __author__ = 'Antons Rebguns' 00039 __copyright__ = 'Copyright (c) 2010-2011 Antons Rebguns' 00040 00041 __license__ = 'BSD' 00042 __maintainer__ = 'Antons Rebguns' 00043 __email__ = 'anton@email.arizona.edu' 00044 00045 00046 from threading import Thread 00047 00048 import roslib 00049 roslib.load_manifest('dynamixel_controllers') 00050 00051 import rospy 00052 import actionlib 00053 00054 from std_msgs.msg import Float64 00055 from trajectory_msgs.msg import JointTrajectory 00056 from control_msgs.msg import FollowJointTrajectoryAction 00057 from control_msgs.msg import FollowJointTrajectoryFeedback 00058 from control_msgs.msg import FollowJointTrajectoryResult 00059 00060 00061 class Segment(): 00062 def __init__(self, num_joints): 00063 self.start_time = 0.0 # trajectory segment start time 00064 self.duration = 0.0 # trajectory segment duration 00065 self.positions = [0.0] * num_joints 00066 self.velocities = [0.0] * num_joints 00067 00068 class JointTrajectoryActionController(): 00069 def __init__(self, controller_namespace, controllers): 00070 self.update_rate = 1000 00071 self.state_update_rate = 50 00072 self.trajectory = [] 00073 00074 self.controller_namespace = controller_namespace 00075 self.joint_names = [c.joint_name for c in controllers] 00076 00077 self.joint_to_controller = {} 00078 for c in controllers: 00079 self.joint_to_controller[c.joint_name] = c 00080 00081 self.port_to_joints = {} 00082 for c in controllers: 00083 if c.port_namespace not in self.port_to_joints: self.port_to_joints[c.port_namespace] = [] 00084 self.port_to_joints[c.port_namespace].append(c.joint_name) 00085 00086 self.port_to_io = {} 00087 for c in controllers: 00088 if c.port_namespace in self.port_to_io: continue 00089 self.port_to_io[c.port_namespace] = c.dxl_io 00090 00091 self.joint_states = dict(zip(self.joint_names, [c.joint_state for c in controllers])) 00092 self.num_joints = len(self.joint_names) 00093 self.joint_to_idx = dict(zip(self.joint_names, range(self.num_joints))) 00094 00095 def initialize(self): 00096 ns = self.controller_namespace + '/joint_trajectory_action_node/constraints' 00097 self.goal_time_constraint = rospy.get_param(ns + '/goal_time', 0.0) 00098 self.stopped_velocity_tolerance = rospy.get_param(ns + '/stopped_velocity_tolerance', 0.01) 00099 self.goal_constraints = [] 00100 self.trajectory_constraints = [] 00101 self.min_velocity = rospy.get_param(self.controller_namespace + '/joint_trajectory_action_node/min_velocity', 0.1) 00102 00103 for joint in self.joint_names: 00104 self.goal_constraints.append(rospy.get_param(ns + '/' + joint + '/goal', -1.0)) 00105 self.trajectory_constraints.append(rospy.get_param(ns + '/' + joint + '/trajectory', -1.0)) 00106 00107 # Message containing current state for all controlled joints 00108 self.msg = FollowJointTrajectoryFeedback() 00109 self.msg.joint_names = self.joint_names 00110 self.msg.desired.positions = [0.0] * self.num_joints 00111 self.msg.desired.velocities = [0.0] * self.num_joints 00112 self.msg.desired.accelerations = [0.0] * self.num_joints 00113 self.msg.actual.positions = [0.0] * self.num_joints 00114 self.msg.actual.velocities = [0.0] * self.num_joints 00115 self.msg.error.positions = [0.0] * self.num_joints 00116 self.msg.error.velocities = [0.0] * self.num_joints 00117 00118 return True 00119 00120 00121 def start(self): 00122 self.running = True 00123 00124 self.command_sub = rospy.Subscriber(self.controller_namespace + '/command', JointTrajectory, self.process_command) 00125 self.state_pub = rospy.Publisher(self.controller_namespace + '/state', FollowJointTrajectoryFeedback) 00126 self.action_server = actionlib.SimpleActionServer(self.controller_namespace + '/follow_joint_trajectory', 00127 FollowJointTrajectoryAction, 00128 execute_cb=self.process_follow_trajectory, 00129 auto_start=False) 00130 self.action_server.start() 00131 Thread(target=self.update_state).start() 00132 00133 def stop(self): 00134 self.running = False 00135 00136 def process_command(self, msg): 00137 if self.action_server.is_active(): self.action_server.set_preempted() 00138 00139 while self.action_server.is_active(): 00140 sleep(0.01) 00141 00142 self.process_trajectory(msg) 00143 00144 def process_follow_trajectory(self, goal): 00145 self.process_trajectory(goal.trajectory) 00146 00147 def process_trajectory(self, traj): 00148 num_points = len(traj.points) 00149 00150 # make sure the joints in the goal match the joints of the controller 00151 if set(self.joint_names) != set(traj.joint_names): 00152 res = FollowJointTrajectoryResult(FollowJointTrajectoryResult.INVALID_JOINTS) 00153 msg = 'Incoming trajectory joints do not match the joints of the controller' 00154 rospy.logerr(msg) 00155 self.action_server.set_aborted(result=res, text=msg) 00156 return 00157 00158 # make sure trajectory is not empty 00159 if num_points == 0: 00160 msg = 'Incoming trajectory is empty' 00161 rospy.logerr(msg) 00162 self.action_server.set_aborted(text=msg) 00163 return 00164 00165 # correlate the joints we're commanding to the joints in the message 00166 # map from an index of joint in the controller to an index in the trajectory 00167 lookup = [traj.joint_names.index(joint) for joint in self.joint_names] 00168 durations = [0.0] * num_points 00169 00170 # find out the duration of each segment in the trajectory 00171 durations[0] = traj.points[0].time_from_start.to_sec() 00172 00173 for i in range(1, num_points): 00174 durations[i] = (traj.points[i].time_from_start - traj.points[i-1].time_from_start).to_sec() 00175 00176 if not traj.points[0].positions: 00177 res = FollowJointTrajectoryResult(FollowJointTrajectoryResult.INVALID_GOAL) 00178 msg = 'First point of trajectory has no positions' 00179 rospy.logerr(msg) 00180 self.action_server.set_aborted(result=res, text=msg) 00181 return 00182 00183 trajectory = [] 00184 time = rospy.Time.now() + rospy.Duration(0.01) 00185 00186 for i in range(num_points): 00187 seg = Segment(self.num_joints) 00188 00189 if traj.header.stamp == rospy.Time(0.0): 00190 seg.start_time = (time + traj.points[i].time_from_start).to_sec() - durations[i] 00191 else: 00192 seg.start_time = (traj.header.stamp + traj.points[i].time_from_start).to_sec() - durations[i] 00193 00194 seg.duration = durations[i] 00195 00196 # Checks that the incoming segment has the right number of elements. 00197 if traj.points[i].velocities and len(traj.points[i].velocities) != self.num_joints: 00198 res = FollowJointTrajectoryResult(FollowJointTrajectoryResult.INVALID_GOAL) 00199 msg = 'Command point %d has %d elements for the velocities' % (i, len(traj.points[i].velocities)) 00200 rospy.logerr(msg) 00201 self.action_server.set_aborted(result=res, text=msg) 00202 return 00203 00204 if len(traj.points[i].positions) != self.num_joints: 00205 res = FollowJointTrajectoryResult(FollowJointTrajectoryResult.INVALID_GOAL) 00206 msg = 'Command point %d has %d elements for the positions' % (i, len(traj.points[i].positions)) 00207 rospy.logerr(msg) 00208 self.action_server.set_aborted(result=res, text=msg) 00209 return 00210 00211 for j in range(self.num_joints): 00212 if traj.points[i].velocities: 00213 seg.velocities[j] = traj.points[i].velocities[lookup[j]] 00214 if traj.points[i].positions: 00215 seg.positions[j] = traj.points[i].positions[lookup[j]] 00216 00217 trajectory.append(seg) 00218 00219 rospy.loginfo('Trajectory start requested at %.3lf, waiting...', traj.header.stamp.to_sec()) 00220 rate = rospy.Rate(self.update_rate) 00221 00222 while traj.header.stamp > time: 00223 time = rospy.Time.now() 00224 rate.sleep() 00225 00226 end_time = traj.header.stamp + rospy.Duration(sum(durations)) 00227 seg_end_times = [rospy.Time.from_sec(trajectory[seg].start_time + durations[seg]) for seg in range(len(trajectory))] 00228 00229 rospy.loginfo('Trajectory start time is %.3lf, end time is %.3lf, total duration is %.3lf', time.to_sec(), end_time.to_sec(), sum(durations)) 00230 00231 self.trajectory = trajectory 00232 traj_start_time = rospy.Time.now() 00233 00234 for seg in range(len(trajectory)): 00235 rospy.logdebug('current segment is %d time left %f cur time %f' % (seg, durations[seg] - (time.to_sec() - trajectory[seg].start_time), time.to_sec())) 00236 rospy.logdebug('goal positions are: %s' % str(trajectory[seg].positions)) 00237 00238 # first point in trajectories calculated by OMPL is current position with duration of 0 seconds, skip it 00239 if durations[seg] == 0: 00240 rospy.logdebug('skipping segment %d with duration of 0 seconds' % seg) 00241 continue 00242 00243 multi_packet = {} 00244 00245 for port,joints in self.port_to_joints.items(): 00246 vals = [] 00247 00248 for joint in joints: 00249 j = self.joint_names.index(joint) 00250 00251 start_position = self.joint_states[joint].current_pos 00252 if seg != 0: start_position = trajectory[seg-1].positions[j] 00253 00254 desired_position = trajectory[seg].positions[j] 00255 desired_velocity = max(self.min_velocity, abs(desired_position - start_position) / durations[seg]) 00256 00257 self.msg.desired.positions[j] = desired_position 00258 self.msg.desired.velocities[j] = desired_velocity 00259 00260 motor_id = self.joint_to_controller[joint].motor_id 00261 pos = self.joint_to_controller[joint].pos_rad_to_raw(desired_position) 00262 spd = self.joint_to_controller[joint].spd_rad_to_raw(desired_velocity) 00263 00264 vals.append((motor_id,pos,spd)) 00265 00266 multi_packet[port] = vals 00267 00268 for port,vals in multi_packet.items(): 00269 self.port_to_io[port].set_multi_position_and_speed(vals) 00270 00271 while time < seg_end_times[seg]: 00272 # check if new trajectory was received, if so abort current trajectory execution 00273 # by setting the goal to the current position 00274 if self.action_server.is_preempt_requested(): 00275 msg = 'New trajectory received. Aborting old trajectory.' 00276 multi_packet = {} 00277 00278 for port,joints in self.port_to_joints.items(): 00279 vals = [] 00280 00281 for joint in joints: 00282 cur_pos = self.joint_states[joint].current_pos 00283 00284 motor_id = self.joint_to_controller[joint].motor_id 00285 pos = self.joint_to_controller[joint].pos_rad_to_raw(cur_pos) 00286 00287 vals.append((motor_id,pos)) 00288 00289 multi_packet[port] = vals 00290 00291 for port,vals in multi_packet.items(): 00292 self.port_to_io[port].set_multi_position(vals) 00293 00294 self.action_server.set_preempted(text=msg) 00295 rospy.logwarn(msg) 00296 return 00297 00298 rate.sleep() 00299 time = rospy.Time.now() 00300 00301 # Verifies trajectory constraints 00302 for j, joint in enumerate(self.joint_names): 00303 if self.trajectory_constraints[j] > 0 and self.msg.error.positions[j] > self.trajectory_constraints[j]: 00304 res = FollowJointTrajectoryResult(FollowJointTrajectoryResult.PATH_TOLERANCE_VIOLATED) 00305 msg = 'Unsatisfied position constraint for %s, trajectory point %d, %f is larger than %f' % \ 00306 (joint, seg, self.msg.error.positions[j], self.trajectory_constraints[j]) 00307 rospy.logwarn(msg) 00308 self.action_server.set_aborted(result=res, text=msg) 00309 return 00310 00311 # let motors roll for specified amount of time 00312 rospy.sleep(self.goal_time_constraint) 00313 00314 for i, j in enumerate(self.joint_names): 00315 rospy.logdebug('desired pos was %f, actual pos is %f, error is %f' % (trajectory[-1].positions[i], self.joint_states[j].current_pos, self.joint_states[j].current_pos - trajectory[-1].positions[i])) 00316 00317 # Checks that we have ended inside the goal constraints 00318 for (joint, pos_error, pos_constraint) in zip(self.joint_names, self.msg.error.positions, self.goal_constraints): 00319 if pos_constraint > 0 and abs(pos_error) > pos_constraint: 00320 res = FollowJointTrajectoryResult(FollowJointTrajectoryResult.GOAL_TOLERANCE_VIOLATED) 00321 msg = 'Aborting because %s joint wound up outside the goal constraints, %f is larger than %f' % \ 00322 (joint, pos_error, pos_constraint) 00323 rospy.logwarn(msg) 00324 self.action_server.set_aborted(result=res, text=msg) 00325 break 00326 else: 00327 res = FollowJointTrajectoryResult(FollowJointTrajectoryResult.SUCCESSFUL) 00328 msg = 'Trajectory execution successfully completed' 00329 rospy.loginfo(msg) 00330 self.action_server.set_succeeded(result=res, text=msg) 00331 00332 def update_state(self): 00333 rate = rospy.Rate(self.state_update_rate) 00334 while self.running and not rospy.is_shutdown(): 00335 self.msg.header.stamp = rospy.Time.now() 00336 00337 # Publish current joint state 00338 for i, joint in enumerate(self.joint_names): 00339 state = self.joint_states[joint] 00340 self.msg.actual.positions[i] = state.current_pos 00341 self.msg.actual.velocities[i] = abs(state.velocity) 00342 self.msg.error.positions[i] = self.msg.actual.positions[i] - self.msg.desired.positions[i] 00343 self.msg.error.velocities[i] = self.msg.actual.velocities[i] - self.msg.desired.velocities[i] 00344 00345 self.state_pub.publish(self.msg) 00346 rate.sleep() 00347