Skip to content

Commit

Permalink
pass start-offset-time to :send-trajectory
Browse files Browse the repository at this point in the history
  • Loading branch information
knorth55 committed Dec 27, 2016
1 parent e3d928f commit 0dc573f
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion pr2eus_moveit/euslisp/robot-moveit.l
Original file line number Diff line number Diff line change
Expand Up @@ -544,7 +544,9 @@

(if use-send-angle-vector
(send* self :joint-trajectory-to-angle-vector-list move-arm traj args)
(send* self :send-trajectory traj args))
(if start-offset-time
(send* self :send-trajectory traj :starttime start-offset-time args)
(send* self :send-trajectory traj args)))
(if (listp av) av (list av)))))
(:move-end-coords-plan ;;
(cds &rest args &key (move-arm :larm) (reset-total-time 5000.0) (use-send-angle-vector) &allow-other-keys)
Expand Down

0 comments on commit 0dc573f

Please sign in to comment.