39 import roslib; roslib.load_manifest(
'velma_task_cs_ros_interface')
45 from velma_common
import *
46 from rcprg_planner
import *
47 from rcprg_ros_utils
import exitError
49 if __name__ ==
"__main__":
51 q_map_starting = {
'torso_0_joint':0,
'right_arm_0_joint':-0.3,
'right_arm_1_joint':-1.8,
52 'right_arm_2_joint':1.25,
'right_arm_3_joint':0.85,
'right_arm_4_joint':0,
'right_arm_5_joint':-0.5,
53 'right_arm_6_joint':0,
'left_arm_0_joint':0.3,
'left_arm_1_joint':1.8,
'left_arm_2_joint':-1.25,
54 'left_arm_3_joint':-0.85,
'left_arm_4_joint':0,
'left_arm_5_joint':0.5,
'left_arm_6_joint':0 }
56 q_map_goal = {
'torso_0_joint':0,
'right_arm_0_joint':-0.3,
'right_arm_1_joint':-1.8,
57 'right_arm_2_joint':-1.25,
'right_arm_3_joint':1.57,
'right_arm_4_joint':0,
'right_arm_5_joint':-0.5,
58 'right_arm_6_joint':0,
'left_arm_0_joint':0.3,
'left_arm_1_joint':1.8,
'left_arm_2_joint':-1.25,
59 'left_arm_3_joint':-0.85,
'left_arm_4_joint':0,
'left_arm_5_joint':0.5,
'left_arm_6_joint':0 }
61 rospy.init_node(
'test_jimp_planning', anonymous=
False)
65 print "This test/tutorial executes complex motions"\
66 " in Joint Impedance mode. Planning is used"\
69 print "Running python interface for Velma..." 70 velma = VelmaInterface()
71 print "Waiting for VelmaInterface initialization..." 72 if not velma.waitForInit(timeout_s=10.0):
73 print "Could not initialize VelmaInterface\n" 75 print "Initialization ok!\n" 77 diag = velma.getCoreCsDiag()
78 if not diag.motorsReady():
79 print "Motors must be homed and ready to use for this test." 82 print "Waiting for Planner initialization..." 83 p = Planner(velma.maxJointTrajLen())
84 if not p.waitForInit(timeout_s=10.0):
85 print "Could not initialize Planner" 87 print "Planner initialization ok!" 89 print "Motors must be enabled every time after the robot enters safe state." 90 print "If the motors are already enabled, enabling them has no effect." 91 print "Enabling motors..." 92 if velma.enableMotors() != 0:
95 print "Switch to jnt_imp mode (no trajectory)..." 96 velma.moveJointImpToCurrentPos(start_time=0.5)
97 error = velma.waitForJoint()
99 print "The action should have ended without error, but the error code is", error
102 print "Checking if the starting configuration is as expected..." 104 js = velma.getLastJointState()
106 print "This test requires starting pose:" 110 print "Planning motion to the goal position using set of all joints..." 112 print "Moving to valid position, using planned trajectory." 113 goal_constraint_1 =
qMapToConstraints(q_map_goal, 0.01, group=velma.getJointGroup(
"impedance_joints"))
116 js = velma.getLastJointState()
117 print "Planning (try", i,
")..." 118 traj = p.plan(js[1], [goal_constraint_1],
"impedance_joints", num_planning_attempts=10, max_velocity_scaling_factor=0.15, planner_id=
"RRTConnect")
121 print "Executing trajectory..." 122 if not velma.moveJointTraj(traj, start_time=0.5, position_tol=10.0/180.0 * math.pi, velocity_tol=10.0/180.0*math.pi):
124 if velma.waitForJoint() == 0:
127 print "The trajectory could not be completed, retrying..." 131 js = velma.getLastJointState()
137 print "Moving to starting position, using planned trajectory." 138 goal_constraint_2 =
qMapToConstraints(q_map_starting, 0.01, group=velma.getJointGroup(
"impedance_joints"))
141 js = velma.getLastJointState()
142 print "Planning (try", i,
")..." 143 traj = p.plan(js[1], [goal_constraint_2],
"impedance_joints", num_planning_attempts=10, max_velocity_scaling_factor=0.15, planner_id=
"RRTConnect")
146 print "Executing trajectory..." 147 if not velma.moveJointTraj(traj, start_time=0.5, position_tol=10.0/180.0 * math.pi, velocity_tol=10.0/180.0*math.pi):
149 if velma.waitForJoint() == 0:
152 print "The trajectory could not be completed, retrying..." 155 js = velma.getLastJointState()
159 print "Planning motion to the same goal position using subset of joints (right arm only)..." 161 print "Moving to valid position, using planned trajectory." 162 goal_constraint_1 =
qMapToConstraints(q_map_goal, 0.01, group=velma.getJointGroup(
"right_arm"))
165 js = velma.getLastJointState()
166 print "Planning (try", i,
")..." 167 traj = p.plan(js[1], [goal_constraint_1],
"right_arm", num_planning_attempts=10, max_velocity_scaling_factor=0.15, planner_id=
"RRTConnect")
170 print "Executing trajectory..." 171 if not velma.moveJointTraj(traj, start_time=0.5, position_tol=10.0/180.0 * math.pi, velocity_tol=10.0/180.0*math.pi):
173 if velma.waitForJoint() == 0:
176 print "The trajectory could not be completed, retrying..." 180 js = velma.getLastJointState()
186 print "Moving to starting position, using planned trajectory." 187 goal_constraint_2 =
qMapToConstraints(q_map_starting, 0.01, group=velma.getJointGroup(
"right_arm"))
190 js = velma.getLastJointState()
191 print "Planning (try", i,
")..." 192 traj = p.plan(js[1], [goal_constraint_2],
"right_arm", num_planning_attempts=10, max_velocity_scaling_factor=0.15, planner_id=
"RRTConnect")
195 print "Executing trajectory..." 196 if not velma.moveJointTraj(traj, start_time=0.5, position_tol=10.0/180.0 * math.pi, velocity_tol=10.0/180.0*math.pi):
198 if velma.waitForJoint() == 0:
201 print "The trajectory could not be completed, retrying..." 204 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.