39 import roslib; roslib.load_manifest(
'velma_task_cs_ros_interface')
46 symmetricalConfiguration
47 from control_msgs.msg
import FollowJointTrajectoryResult
48 from rcprg_ros_utils
import exitError
50 if __name__ ==
"__main__":
55 'right_arm_0_joint':0,
'right_arm_1_joint':0,
'right_arm_2_joint':0,
56 'right_arm_3_joint':0,
'right_arm_4_joint':0,
'right_arm_5_joint':0,
57 'right_arm_6_joint':0} )
61 'right_arm_0_joint':-0.3,
'right_arm_1_joint':-1.8,
'right_arm_2_joint':1.25,
62 'right_arm_3_joint':0.85,
'right_arm_4_joint':0,
'right_arm_5_joint':-0.5,
63 'right_arm_6_joint':0,} )
66 q_map_goal = {
'torso_0_joint':0,
67 'right_arm_0_joint':-0.3,
'right_arm_1_joint':-1.8,
'right_arm_2_joint':-1.25,
68 'right_arm_3_joint':2.0,
'right_arm_4_joint':0,
'right_arm_5_joint':-0.5,
69 'right_arm_6_joint':0,
70 'left_arm_0_joint':0.3,
'left_arm_1_joint':1.8,
'left_arm_2_joint':-1.25,
71 'left_arm_3_joint':-0.85,
'left_arm_4_joint':0,
'left_arm_5_joint':0.5,
72 'left_arm_6_joint':0 }
75 q_map_intermediate = {
'torso_0_joint':0,
76 'right_arm_0_joint':-0.3,
'right_arm_1_joint':-1.6,
'right_arm_2_joint':-1.25,
77 'right_arm_3_joint':-0.85,
'right_arm_4_joint':0,
'right_arm_5_joint':-0.5,
78 'right_arm_6_joint':0,
79 'left_arm_0_joint':0.3,
'left_arm_1_joint':1.8,
'left_arm_2_joint':-1.25,
80 'left_arm_3_joint':-0.85,
'left_arm_4_joint':0,
'left_arm_5_joint':0.5,
81 'left_arm_6_joint':0 }
83 rospy.init_node(
'test_jimp')
87 print(
"This test/tutorial executes simple motions"\
88 " in joint impedance mode. Planning is not used"\
91 print(
"Running python interface for Velma...")
93 print(
"Waiting for VelmaInterface initialization...")
94 if not velma.waitForInit(timeout_s=10.0):
95 exitError(1, msg=
"Could not initialize VelmaInterface")
96 print(
"Initialization ok!")
98 print(
"Motors must be enabled every time after the robot enters safe state.")
99 print(
"If the motors are already enabled, enabling them has no effect.")
100 print(
"Enabling motors...")
101 if velma.enableMotors() != 0:
102 exitError(2, msg=
"Could not enable motors")
106 diag = velma.getCoreCsDiag()
107 if not diag.motorsReady():
108 exitError(1, msg=
"Motors must be homed and ready to use for this test.")
111 print(
"Switch to jnt_imp mode (no trajectory)...")
112 velma.moveJointImpToCurrentPos(start_time=0.5)
113 error = velma.waitForJoint()
115 exitError(3, msg=
"The action should have ended without error,"\
116 " but the error code is {}".format(error))
118 print(
"Checking if the starting configuration is as expected...")
120 js = velma.getLastJointState()
122 exitError(10, msg=
"This test requires starting pose: {}".format(q_map_starting))
124 print(
"Moving to position 0 (this motion is too fast and should cause error condition,"\
125 " that leads to safe mode in velma_core_cs).")
126 velma.moveJoint(q_map_0, 0.05, start_time=0.5, position_tol=0, velocity_tol=0)
127 error = velma.waitForJoint()
128 if error != FollowJointTrajectoryResult.PATH_TOLERANCE_VIOLATED:
129 exitError(4, msg=
"The action should have ended with PATH_TOLERANCE_VIOLATED"\
130 " error status, but the error code is {}".format(error) )
132 print(
"Checking if current pose is close to the starting pose...")
134 js = velma.getLastJointState()
138 print(
"waiting 2 seconds...")
141 print(
"Motors must be enabled every time after the robot enters safe state.")
142 print(
"If the motors are already enabled, enabling them has no effect.")
143 print(
"Enabling motors...")
144 if velma.enableMotors() != 0:
147 print(
"Moving to position 0 (slowly).")
148 velma.moveJoint(q_map_0, 9.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
152 js = velma.getLastJointState()
158 print(
"Moving to the starting position...")
159 velma.moveJoint(q_map_starting, 9.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
160 error = velma.waitForJoint()
162 exitError(6, msg=
"The action should have ended without error,"\
163 " but the error code is {}".format(error))
166 js = velma.getLastJointState()
170 print(
"Moving to valid position, using invalid self-colliding trajectory"\
171 " (this motion should cause error condition, that leads to safe mode in velma_core_cs).")
172 velma.moveJoint(q_map_goal, 9.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
173 error = velma.waitForJoint()
174 if error != FollowJointTrajectoryResult.PATH_TOLERANCE_VIOLATED:
175 exitError(7, msg=
"The action should have ended with PATH_TOLERANCE_VIOLATED"\
176 " error status, but the error code is {}".format(error) )
178 print(
"Using relax behavior to exit self collision...")
179 velma.switchToRelaxBehavior()
181 print(
"waiting 2 seconds...")
184 print(
"Motors must be enabled every time after the robot enters safe state.")
185 print(
"If the motors are already enabled, enabling them has no effect.")
186 print(
"Enabling motors...")
187 if velma.enableMotors() != 0:
190 print(
"Moving to the starting position...")
191 velma.moveJoint(q_map_starting, 4.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
192 error = velma.waitForJoint()
194 exitError(9, msg=
"The action should have ended without error,"\
195 " but the error code is {}".format(error))
198 js = velma.getLastJointState()
202 print(
"To reach the goal position, some trajectory must be exetuted that contains additional,"\
203 " intermediate nodes")
205 print(
"Moving to the intermediate position...")
206 velma.moveJoint(q_map_intermediate, 8.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
207 error = velma.waitForJoint()
209 exitError(10, msg=
"The action should have ended without error,"\
210 " but the error code is {}".format(error))
213 js = velma.getLastJointState()
217 print(
"Moving to the goal position.")
218 velma.moveJoint(q_map_goal, 8.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
219 error = velma.waitForJoint()
221 exitError(11, msg=
"The action should have ended with PATH_TOLERANCE_VIOLATED"\
222 " error status, but the error code is {}".format(error) )
225 js = velma.getLastJointState()
229 print(
"Moving to the intermediate position...")
230 velma.moveJoint(q_map_intermediate, 8.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
231 error = velma.waitForJoint()
233 exitError(12, msg=
"The action should have ended without error,"\
234 " but the error code is {}".format(error))
237 js = velma.getLastJointState()
241 print(
"Moving to the starting position...")
242 velma.moveJoint(q_map_starting, 5.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
243 error = velma.waitForJoint()
245 exitError(13, msg=
"The action should have ended without error,"\
246 " but the error code is {}".format(error))
249 js = velma.getLastJointState()
def isConfigurationClose(q_map1, q_map2, tolerance=0.1, allow_subset=False)
Check if two configurations of robot body are close within tolerance.
ROS-based, Python interface class for WUT Velma Robot.
def symmetricalConfiguration(q_map)
Get configuration based on the input configuration such that all joint positions are symmetrical...