Go to the documentation of this file.00001
00002
00003 """
00004 Copyright (c) 2011 Vanadium Labs LLC.
00005 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 roslib; roslib.load_manifest('mini_max_apps')
00031 import rospy
00032 import actionlib
00033 import sys
00034
00035 from actionlib_msgs.msg import GoalStatus
00036 from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
00037 from control_msgs.msg import *
00038
00039 servos = ['arm_wrist_flex_joint', 'arm_shoulder_lift_joint', 'arm_shoulder_pan_joint', 'arm_elbow_flex_joint']
00040 tucked = [1.5084144414208807, -0.71585770101329926, 1.4726215563702156, 1.9634954084936207]
00041 utcked = [1.5135277107138327, 0.015339807878856412, 1.5288675185926892, 1.5544338650574498]
00042
00043 if __name__ == '__main__':
00044 rospy.init_node('tuck_arm')
00045
00046
00047 client = actionlib.SimpleActionClient('follow_joint_trajectory', FollowJointTrajectoryAction)
00048 client.wait_for_server()
00049
00050
00051 msg = JointTrajectory()
00052 msg.joint_names = servos
00053 msg.points = list()
00054
00055
00056 if len(sys.argv) > 1 and sys.argv[1] == "u":
00057 point = JointTrajectoryPoint()
00058 point.positions = utcked
00059 point.velocities = [ 0.0 for servo in msg.joint_names ]
00060 point.time_from_start = rospy.Duration(3.0)
00061 msg.points.append(point)
00062 else:
00063 point = JointTrajectoryPoint()
00064 point.positions = utcked
00065 point.velocities = [ 0.0 for servo in msg.joint_names ]
00066 point.time_from_start = rospy.Duration(5.0)
00067 msg.points.append(point)
00068 point = JointTrajectoryPoint()
00069 point.positions = tucked
00070 point.velocities = [ 0.0 for servo in msg.joint_names ]
00071 point.time_from_start = rospy.Duration(8.0)
00072 msg.points.append(point)
00073
00074
00075 msg.header.stamp = rospy.Time.now()
00076 goal = FollowJointTrajectoryGoal()
00077 goal.trajectory = msg
00078 client.send_goal(goal)
00079 client.wait_for_result()
00080