4 follow_controller.py - controller for a kinematic chain 5 Copyright (c) 2011 Vanadium Labs LLC. All right reserved. 7 Redistribution and use in source and binary forms, with or without 8 modification, are permitted provided that the following conditions are met: 9 * Redistributions of source code must retain the above copyright 10 notice, this list of conditions and the following disclaimer. 11 * Redistributions in binary form must reproduce the above copyright 12 notice, this list of conditions and the following disclaimer in the 13 documentation and/or other materials provided with the distribution. 14 * Neither the name of Vanadium Labs LLC nor the names of its 15 contributors may be used to endorse or promote products derived 16 from this software without specific prior written permission. 18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 19 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 20 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 21 DISCLAIMED. IN NO EVENT SHALL VANADIUM LABS BE LIABLE FOR ANY DIRECT, INDIRECT, 22 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 23 LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 24 OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 25 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE 26 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF 27 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 import rospy, actionlib
32 from control_msgs.msg
import FollowJointTrajectoryAction
33 from trajectory_msgs.msg
import JointTrajectory
37 from controllers
import *
40 """ A controller for joint chains, exposing a FollowJointTrajectory action. """ 43 Controller.__init__(self, device, name)
47 self.
rate = rospy.get_param(
'~controllers/'+name+
'/rate',50.0)
48 self.
joints = rospy.get_param(
'~controllers/'+name+
'/joints')
49 self.
index = rospy.get_param(
'~controllers/'+name+
'/index', len(device.controllers))
51 self.
device.joints[joint].controller = self
54 name = rospy.get_param(
'~controllers/'+name+
'/action_name',
'follow_joint_trajectory')
58 rospy.Subscriber(self.
name+
'/command', JointTrajectory, self.
commandCb)
61 rospy.loginfo(
"Started FollowController ("+self.
name+
"). Joints: " + str(self.
joints) +
" on C" + str(self.
index))
67 rospy.loginfo(self.
name +
": Action goal recieved.")
68 traj = goal.trajectory
70 if set(self.
joints) != set(traj.joint_names):
72 if j
not in traj.joint_names:
73 msg =
"Trajectory joint names does not match action controlled joints." + str(traj.joint_names)
75 self.
server.set_aborted(text=msg)
77 rospy.logwarn(
"Extra joints in trajectory")
80 msg =
"Trajectory empy." 82 self.
server.set_aborted(text=msg)
86 indexes = [traj.joint_names.index(joint)
for joint
in self.
joints]
87 except ValueError
as val:
88 msg =
"Trajectory invalid." 90 self.
server.set_aborted(text=msg)
95 self.
server.set_succeeded()
96 rospy.loginfo(self.
name +
": Done.")
98 self.
server.set_preempted(text=
"Goal canceled.")
99 rospy.loginfo(self.
name +
": Goal canceled.")
101 self.
server.set_aborted(text=
"Execution failed.")
102 rospy.loginfo(self.
name +
": Execution failed.")
107 if self.
server.is_active():
108 rospy.loginfo(self.
name+
": Received trajectory, but action is active")
115 rospy.loginfo(
"Executing trajectory")
119 indexes = [traj.joint_names.index(joint)
for joint
in self.
joints]
120 except ValueError
as val:
121 rospy.logerr(
"Invalid joint in trajectory.")
125 start = traj.header.stamp
126 if start.secs == 0
and start.nsecs == 0:
127 start = rospy.Time.now()
129 r = rospy.Rate(self.
rate)
130 last = [ self.
device.joints[joint].position
for joint
in self.
joints ]
131 for point
in traj.points:
132 while rospy.Time.now() + rospy.Duration(0.01) < start:
133 if self.
server.is_preempt_requested():
136 desired = [ point.positions[k]
for k
in indexes ]
137 endtime = start + point.time_from_start
138 while rospy.Time.now() + rospy.Duration(0.01) < endtime:
140 if self.
server.is_preempt_requested():
143 err = [ (d-c)
for d,c
in zip(desired,last) ]
144 velocity = [ abs(x / (self.
rate * (endtime - rospy.Time.now()).to_sec()))
for x
in err ]
146 for i
in range(len(self.
joints)):
147 if err[i] > 0.001
or err[i] < -0.001:
155 self.
device.joints[self.
joints[i]].setControlOutput(last[i])
162 """ Is controller overriding servo internal control? """ 166 """ Get a diagnostics status. """ 167 msg = DiagnosticStatus()
169 msg.level = DiagnosticStatus.OK
172 msg.values.append(KeyValue(
"State",
"Active"))
174 msg.values.append(KeyValue(
"State",
"Not Active"))
def __init__(self, device, name)
Controllers interact with ArbotiX hardware.
def active(self)
Is the controller actively sending commands to joints?
def executeTrajectory(self, traj)