$search
00001 #!/usr/bin/env python 00002 00003 """ 00004 reset_arm_server.py - a simple service to reset the arm 00005 Copyright (c) 2011 Vanadium Labs LLC. 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 the copyright holders 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('simple_arm_actions') 00031 import rospy, actionlib 00032 00033 from control_msgs.msg import * 00034 from simple_arm_actions.msg import * 00035 from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint 00036 00037 class ResetArmServer: 00038 00039 def __init__(self): 00040 rospy.init_node("reset_arm_server") 00041 try: 00042 self.joints = rospy.get_param("~joints") 00043 except: 00044 self.joints = rospy.get_param("/simple_arms/joints") 00045 00046 self.client = actionlib.SimpleActionClient('follow_joint_trajectory', FollowJointTrajectoryAction) 00047 self.client.wait_for_server() 00048 00049 self.server = actionlib.SimpleActionServer("reset_arm", ResetArmAction, execute_cb=self.actionCb, auto_start=False) 00050 self.server.start() 00051 00052 rospy.spin() 00053 00054 def actionCb(self, req): 00055 goal = FollowJointTrajectoryGoal() 00056 msg = JointTrajectory() 00057 msg.joint_names = self.joints 00058 msg.points = list() 00059 point = JointTrajectoryPoint() 00060 point.positions = [ 0.0 for servo in msg.joint_names ] 00061 point.velocities = [ 0.0 for servo in msg.joint_names ] 00062 point.time_from_start = rospy.Duration(2.0) 00063 msg.points.append(point) 00064 msg.header.stamp = rospy.Time.now() + rospy.Duration(0.01) 00065 goal.trajectory = msg 00066 00067 self.client.send_goal(goal) 00068 self.client.wait_for_result() 00069 self.server.set_succeeded( ResetArmResult() ) 00070 00071 00072 if __name__ == '__main__': 00073 try: 00074 ResetArmServer() 00075 except rospy.ROSInterruptException: 00076 rospy.loginfo("And that's all folks...") 00077