Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 import roslib; roslib.load_manifest('visual_servo')
00035 import rospy
00036 from geometry_msgs.msg import TwistStamped
00037 from geometry_msgs.msg import PoseStamped
00038 import tf
00039 from visual_servo.srv import *
00040
00041
00042 import visual_servo.position_feedback_push_node as pn
00043 import sys
00044 import numpy as np
00045 from math import sqrt
00046
00047 LEFT_ARM_READY_JOINTS = np.matrix([[0.62427649, 0.4556137,
00048 1.63411927, -2.11931035,
00049 -15.38839978, -1.64163257,
00050 -17.2947453]]).T
00051 RIGHT_ARM_READY_JOINTS = np.matrix([[-0.42427649, 0.0656137,
00052 -1.43411927, -2.11931035,
00053 15.78839978, -1.64163257,
00054 8.64421842e+01]]).T
00055
00056 class ArmController:
00057
00058 def __init__(self):
00059
00060 rospy.loginfo('Initializing Arm Controller')
00061
00062 self.pn = pn.PositionFeedbackPushNode()
00063 self.l_cart_twist_pub = self.pn.l_arm_cart_vel_pub
00064 self.r_cart_twist_pub = self.pn.r_arm_cart_vel_pub
00065 self.l_cart_pub = self.pn.l_arm_cart_pub
00066 self.r_cart_pub = self.pn.r_arm_cart_pub
00067 self.pn.init_spine_pose()
00068 self.pn.init_head_pose(self.pn.head_pose_cam_frame)
00069 self.pn.init_arms()
00070
00071 self.pn.gripper_open('l')
00072 self.pn.gripper_open('r')
00073
00074
00075 self.pn.switch_to_cart_controllers()
00076
00077
00078 self.vel_sat_param = rospy.get_param('/arm_controller/vel_sat_param', 0.20)
00079 self.vel_scale_param = rospy.get_param('/arm_controller/vel_scale_param', 0.20)
00080
00081 rospy.loginfo('Done moving to robot initial pose')
00082
00083
00084
00085 def adjust_velocity(self, vel):
00086 ret = vel * self.vel_scale
00087 if ret > self.vel_sat:
00088 ret = self.vel_sat
00089 elif -ret > self.vel_sat:
00090 ret = -self.vel_sat
00091 return ret
00092
00093 def handle_pose_request(self, req):
00094 pose = req.p
00095 which_arm = req.arm
00096 if which_arm == 'l':
00097 self.pn.move_to_cart_pose(pose, 'l')
00098 else:
00099 self.pn.move_to_cart_pose(pose, 'r')
00100 rospy.loginfo(pose)
00101 return {'result': 0}
00102
00103 def handle_twist_request(self, req):
00104 t = req.twist
00105 e = req.error
00106 which_arm = req.arm
00107
00108 self.vel_scale = sqrt(e + self.vel_scale_param)
00109 self.vel_sat = sqrt(e * self.vel_sat_param)
00110 if self.vel_sat > 0.08:
00111 self.vel_sat = 0.08
00112 try:
00113 twist = TwistStamped()
00114 twist.header.stamp = rospy.Time(0)
00115 twist.header.frame_id = 'torso_lift_link'
00116
00117
00118 twist.twist.linear.x = self.adjust_velocity(t.twist.linear.x)
00119 twist.twist.linear.y = self.adjust_velocity(t.twist.linear.y)
00120 twist.twist.linear.z = self.adjust_velocity(t.twist.linear.z)
00121 twist.twist.angular.x = self.adjust_velocity(t.twist.angular.x)
00122 twist.twist.angular.y = self.adjust_velocity(t.twist.angular.y)
00123 twist.twist.angular.z = self.adjust_velocity(t.twist.angular.z)
00124 if which_arm == 'l':
00125 vel_pub = self.pn.l_arm_cart_vel_pub
00126 posture_pub = self.pn.l_arm_vel_posture_pub
00127 m = self.pn.get_desired_posture('l')
00128 else:
00129 vel_pub = self.pn.r_arm_cart_vel_pub
00130 posture_pub = self.pn.r_arm_vel_posture_pub
00131 m = self.pn.get_desired_posture('r')
00132 posture_pub.publish(m)
00133 vel_pub.publish(twist)
00134
00135
00136 rospy.loginfo('[e=%.4f][sca=%.4f][sat=%.4f] x:%+.3f(%+.3f) y:%+.3f(%+.3f) z:%+.3f(%+.3f)', e, self.vel_scale, self.vel_sat, \
00137 twist.twist.linear.x, t.twist.linear.x, \
00138 twist.twist.linear.y, t.twist.linear.y, \
00139 twist.twist.linear.z, t.twist.linear.z)
00140 rospy.loginfo('[angular] x:%+.3f(%+.3f) y:%+.3f(%+.3f) z:%+.3f(%+.3f)', \
00141 twist.twist.angular.x, t.twist.angular.x, \
00142 twist.twist.angular.y, t.twist.angular.y, \
00143 twist.twist.angular.z, t.twist.angular.z)
00144 except rospy.ServiceException, e:
00145 if which_arm == 'l':
00146 self.pn.stop_moving_vel('l')
00147 else:
00148 self.pn.stop_moving_vel('r')
00149
00150 return VisualServoTwistResponse()
00151
00152 def handle_init_request(self, req):
00153 self.pn.init_arms()
00154
00155 if __name__ == '__main__':
00156 try:
00157 node = ArmController()
00158 rospy.loginfo('Done initializing... Now advertise the Service')
00159 rospy.Service('vs_pose', VisualServoPose , node.handle_pose_request)
00160 rospy.Service('vs_twist', VisualServoTwist , node.handle_twist_request)
00161 rospy.Service('vs_init', Empty , node.handle_init_request)
00162 rospy.loginfo('Ready to move arm')
00163 rospy.spin()
00164
00165 except rospy.ROSInterruptException: pass