Skip to content

Commit 01183ad

Browse files
committed
add subscriber for JointTrajectory as /command
1 parent 69249c2 commit 01183ad

File tree

1 file changed

+115
-0
lines changed

1 file changed

+115
-0
lines changed

src/joint_trajectory_action/joint_trajectory_action.py

Lines changed: 115 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,7 @@
4747
)
4848
from trajectory_msgs.msg import (
4949
JointTrajectoryPoint,
50+
JointTrajectory
5051
)
5152

5253
import baxter_control
@@ -63,6 +64,7 @@ def __init__(self, limb, reconfig_server, rate=100.0, mode='position'):
6364
FollowJointTrajectoryAction,
6465
execute_cb=self._on_trajectory_action,
6566
auto_start=False)
67+
self._command = rospy.Subscriber('robot/limb/' + limb + '/command', JointTrajectory, self._on_joint_trajectory)
6668
self._action_name = rospy.get_name()
6769
self._server.start()
6870
self._limb = baxter_interface.Limb(limb)
@@ -213,6 +215,7 @@ def _command_stop(self, joint_names, joint_angles):
213215
def _command_joints(self, joint_names, point):
214216
if self._server.is_preempt_requested():
215217
rospy.loginfo("%s: Trajectory Preempted" % (self._action_name,))
218+
rospy.logerr("%s: Trajectory Preempted" % (self._action_name,))
216219
self._server.set_preempted()
217220
self._command_stop(joint_names, self._limb.joint_angles())
218221
return False
@@ -510,3 +513,115 @@ def check_goal_state():
510513
self._result.error_code = self._result.GOAL_TOLERANCE_VIOLATED
511514
self._server.set_aborted(self._result)
512515
self._command_stop(goal.trajectory.joint_names, end_angles)
516+
517+
def _get_trajectory_parameters(self, joint_names):
518+
# For each input trajectory, if path, goal, or goal_time tolerances
519+
# provided, we will use these as opposed to reading from the
520+
# parameter server/dynamic reconfigure
521+
522+
# Goal time tolerance - time buffer allowing goal constraints to be met
523+
self._goal_time = self._dyn.config['goal_time']
524+
525+
# Stopped velocity tolerance - max velocity at end of execution
526+
self._stopped_velocity = self._dyn.config['stopped_velocity_tolerance']
527+
528+
# Path execution and goal tolerances per joint
529+
for jnt in joint_names:
530+
if not jnt in self._limb.joint_names():
531+
rospy.logerr(
532+
"%s: Trajectory Aborted - Provided Invalid Joint Name %s" %
533+
(self._action_name, jnt,))
534+
self._result.error_code = self._result.INVALID_JOINTS
535+
self._server.set_aborted(self._result)
536+
return
537+
# Path execution tolerance
538+
path_error = self._dyn.config[jnt + '_trajectory']
539+
self._path_thresh[jnt] = path_error
540+
541+
# Goal error tolerance
542+
goal_error = self._dyn.config[jnt + '_goal']
543+
self._goal_error[jnt] = goal_error
544+
545+
# PID gains if executing using the velocity (integral) controller
546+
if self._mode == 'velocity':
547+
self._pid[jnt].set_kp(self._dyn.config[jnt + '_kp'])
548+
self._pid[jnt].set_ki(self._dyn.config[jnt + '_ki'])
549+
self._pid[jnt].set_kd(self._dyn.config[jnt + '_kd'])
550+
self._pid[jnt].initialize()
551+
552+
def _on_joint_trajectory(self, trajectory):
553+
joint_names = trajectory.joint_names
554+
trajectory_points = trajectory.points
555+
556+
rospy.loginfo("%s: Executing requested joint trajectory" %
557+
(self._action_name,))
558+
559+
# Clear spline coefficients
560+
for jnt in xrange(len(joint_names)):
561+
self._coeff[jnt] = [0.0] * 6
562+
563+
# Load parameters for trajectory
564+
self._get_trajectory_parameters(joint_names)
565+
566+
# Create a new discretized joint trajectory
567+
num_points = len(trajectory_points)
568+
569+
if num_points == 0:
570+
rospy.logerr("%s: Empty Trajectory" % (self._command,))
571+
return
572+
573+
end_time = trajectory_points[-1].time_from_start.to_sec()
574+
control_rate = rospy.Rate(self._control_rate)
575+
576+
pnt_times = [pnt.time_from_start.to_sec() for pnt in trajectory_points]
577+
578+
#
579+
start_point = JointTrajectoryPoint()
580+
start_point.positions = self._get_current_position(joint_names)
581+
start_point.velocities = self._get_current_velocities(joint_names)
582+
start_point.accelerations = [0.0] * len(joint_names)
583+
584+
# Wait for the specified execution time, if not provided use now
585+
start_time = trajectory.header.stamp.to_sec()
586+
if start_time == 0.0:
587+
start_time = rospy.get_time()
588+
baxter_dataflow.wait_for(
589+
lambda: rospy.get_time() >= start_time,
590+
timeout=float('inf')
591+
)
592+
593+
# Loop until end of trajectory time. Provide a single time step
594+
# of the control rate past the end to ensure we get to the end.
595+
now_from_start = rospy.get_time() - start_time
596+
# Keep track of current indices for spline segment generation
597+
last_idx = -1
598+
while (now_from_start < end_time and not rospy.is_shutdown()):
599+
idx = bisect.bisect(pnt_times, now_from_start)
600+
601+
if idx == 0:
602+
# If our current time is before the first specified point
603+
# in the trajectory, then we should interpolate between
604+
# our start position and that point.
605+
p1 = deepcopy(start_point)
606+
else:
607+
p1 = deepcopy(trajectory_points[idx - 1])
608+
609+
if idx != num_points:
610+
p2 = trajectory_points[idx]
611+
# If entering a new trajectory segment, calculate coefficients
612+
if last_idx != idx:
613+
self._compute_spline_coefficients(p1, p2)
614+
# Find goal command point at commanded time
615+
cmd_time = now_from_start - p1.time_from_start.to_sec()
616+
point = self._get_point(joint_names, cmd_time)
617+
else:
618+
# If the current time is after the last trajectory point,
619+
# just hold that position.
620+
point = p1
621+
622+
if not self._command_joints(joint_names, point):
623+
return
624+
625+
control_rate.sleep()
626+
now_from_start = rospy.get_time() - start_time
627+
last_idx = idx

0 commit comments

Comments
 (0)