39 import roslib; roslib.load_manifest(
'velma_task_cs_ros_interface')
44 from threading
import Thread
46 from velma_common
import *
47 from rcprg_planner
import *
48 from rcprg_ros_utils
import MarkerPublisher, exitError
50 from moveit_msgs.msg
import AttachedCollisionObject, CollisionObject
51 from shape_msgs.msg
import SolidPrimitive
54 import tf_conversions.posemath
as pm
58 pub = MarkerPublisher(
"attached_objects")
60 pub.publishSinglePointMarker(PyKDL.Vector(), 1, r=1, g=0, b=0, a=1, namespace=
'default', frame_id=obj.link_name, m_type=Marker.CYLINDER, scale=Vector3(0.02, 0.02, 1.0), T=pm.fromMsg(obj.object.primitive_poses[0]))
67 pub.eraseMarkers(0, 10, namespace=
'default')
83 if __name__ ==
"__main__":
85 rospy.init_node(
'test_jimp_planning_attached', anonymous=
False)
89 print "This test/tutorial executes complex motions"\
90 " in Joint Impedance mode with additional objects"\
91 " attached to end-effectors. Planning is used"\
94 print "Running python interface for Velma..." 95 velma = VelmaInterface()
96 print "Waiting for VelmaInterface initialization..." 97 if not velma.waitForInit(timeout_s=10.0):
98 print "Could not initialize VelmaInterface\n" 100 print "Initialization ok!\n" 102 diag = velma.getCoreCsDiag()
103 if not diag.motorsReady():
104 print "Motors must be homed and ready to use for this test." 107 print "Waiting for Planner initialization..." 108 p = Planner(velma.maxJointTrajLen())
109 if not p.waitForInit(timeout_s=10.0):
110 print "Could not initialize Planner" 112 print "Planner initialization ok!" 114 print "Motors must be enabled every time after the robot enters safe state." 115 print "If the motors are already enabled, enabling them has no effect." 116 print "Enabling motors..." 117 if velma.enableMotors() != 0:
120 print "Moving to the current position..." 121 js_start = velma.getLastJointState()
122 velma.moveJoint(js_start[1], 1.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
123 error = velma.waitForJoint()
125 print "The action should have ended without error, but the error code is", error
128 print "Creating a virtual object attached to gripper..." 131 object1 = AttachedCollisionObject()
132 object1.link_name =
"right_HandGripLink" 133 object1.object.header.frame_id =
"right_HandGripLink" 134 object1.object.id =
"object1" 135 object1_prim = SolidPrimitive()
136 object1_prim.type = SolidPrimitive.CYLINDER
137 object1_prim.dimensions=[
None,
None]
138 object1_prim.dimensions[SolidPrimitive.CYLINDER_HEIGHT] = 1.0
139 object1_prim.dimensions[SolidPrimitive.CYLINDER_RADIUS] = 0.02
140 object1_pose = pm.toMsg(PyKDL.Frame(PyKDL.Rotation.RotY(math.pi/2)))
141 object1.object.primitives.append(object1_prim)
142 object1.object.primitive_poses.append(object1_pose)
143 object1.object.operation = CollisionObject.ADD
144 object1.touch_links = [
'right_HandPalmLink',
145 'right_HandFingerOneKnuckleOneLink',
146 'right_HandFingerOneKnuckleTwoLink',
147 'right_HandFingerOneKnuckleThreeLink',
148 'right_HandFingerTwoKnuckleOneLink',
149 'right_HandFingerTwoKnuckleTwoLink',
150 'right_HandFingerTwoKnuckleThreeLink',
151 'right_HandFingerThreeKnuckleTwoLink',
152 'right_HandFingerThreeKnuckleThreeLink']
154 print "Publishing the attached object marker on topic /attached_objects" 158 q_map_goal = {
'torso_0_joint':0,
159 'right_arm_0_joint':-0.3,
160 'right_arm_1_joint':-1.8,
161 'right_arm_2_joint':-1.25,
162 'right_arm_3_joint':1.57,
163 'right_arm_4_joint':0,
164 'right_arm_5_joint':-0.5,
165 'right_arm_6_joint':0,
166 'left_arm_0_joint':0.3,
167 'left_arm_1_joint':1.8,
168 'left_arm_2_joint':-1.25,
169 'left_arm_3_joint':-0.85,
170 'left_arm_4_joint':0,
171 'left_arm_5_joint':0.5,
175 print "Planning motion to the goal position using set of all joints..." 177 print "Moving to valid position, using planned trajectory." 178 goal_constraint_1 =
qMapToConstraints(q_map_goal, 0.01, group=velma.getJointGroup(
"impedance_joints"))
181 js = velma.getLastJointState()
182 print "Planning (try", i,
")..." 183 traj = p.plan(js[1], [goal_constraint_1],
"impedance_joints", max_velocity_scaling_factor=0.15, planner_id=
"RRTConnect", attached_collision_objects=[object1])
186 print "Executing trajectory..." 187 if not velma.moveJointTraj(traj, start_time=0.5):
189 if velma.waitForJoint() == 0:
192 print "The trajectory could not be completed, retrying..." 196 js = velma.getLastJointState()
202 q_map_end = {
'torso_0_joint':0,
203 'right_arm_0_joint':-0.3,
204 'right_arm_1_joint':-1.8,
205 'right_arm_2_joint':1.25,
206 'right_arm_3_joint':0.85,
207 'right_arm_4_joint':0,
208 'right_arm_5_joint':-0.5,
209 'right_arm_6_joint':0,
210 'left_arm_0_joint':0.3,
211 'left_arm_1_joint':1.8,
212 'left_arm_2_joint':-1.25,
213 'left_arm_3_joint':-0.85,
214 'left_arm_4_joint':0,
215 'left_arm_5_joint':0.5,
219 print "Moving to starting position, using planned trajectory." 220 goal_constraint_2 =
qMapToConstraints(q_map_end, 0.01, group=velma.getJointGroup(
"impedance_joints"))
223 js = velma.getLastJointState()
224 print "Planning (try", i,
")..." 225 traj = p.plan(js[1], [goal_constraint_2],
"impedance_joints", max_velocity_scaling_factor=0.15, planner_id=
"RRTConnect", attached_collision_objects=[object1])
228 print "Executing trajectory..." 229 if not velma.moveJointTraj(traj, start_time=0.5):
231 if velma.waitForJoint() == 0:
234 print "The trajectory could not be completed, retrying..." 237 js = velma.getLastJointState()
def qMapToConstraints(q_map, tolerance=0.01, group=None)
This function converts dictionary of joint positions to moveit_msgs.Constraints structure.
def isConfigurationClose(q_map1, q_map2, tolerance=0.1, allow_subset=False)
Check if two configurations of robot body are close within tolerance.
def threaded_function(self, obj)