1515from std_srvs .srv import Trigger , TriggerRequest
1616import tf
1717from trajectory_msgs .msg import JointTrajectoryPoint
18- from geometry_msgs .msg import Pose , PoseStamped , Quaternion , Point , WrenchStamped , TwistStamped , Wrench , Twist , Vector3
18+ from geometry_msgs .msg import Pose , PoseStamped , Quaternion , Point , Wrench , Twist , Vector3
1919from ur_msgs .srv import SetIO , SetIORequest , GetRobotSoftwareVersion , SetForceModeRequest , SetForceMode
2020from ur_msgs .msg import IOStates
2121
@@ -128,9 +128,9 @@ def init_robot(self):
128128 self .fail ("Could not reach start force mode service. Make sure that the driver is actually running."
129129 " Msg: {}" .format (err ))
130130
131- self .end_force_mode_srv = rospy .ServiceProxy ('/ur_hardware_interface/end_force_mode ' , Trigger )
131+ self .stop_force_mode_srv = rospy .ServiceProxy ('/ur_hardware_interface/stop_force_mode ' , Trigger )
132132 try :
133- self .end_force_mode_srv .wait_for_service (timeout )
133+ self .stop_force_mode_srv .wait_for_service (timeout )
134134 except rospy .exceptions .ROSException as err :
135135 self .fail ("Could not reach end force mode service. Make sure that the driver is actually running."
136136 " Msg: {}" .format (err ))
@@ -159,6 +159,7 @@ def set_robot_to_mode(self, target_mode):
159159 return self .set_mode_client .get_result ().success
160160
161161 def test_force_mode_srv (self ):
162+ req = SetForceModeRequest ()
162163 point = Point (0.1 , 0.1 , 0.1 )
163164 orientation = Quaternion (0 , 0 , 0 , 0 )
164165 task_frame_pose = Pose (point , orientation )
@@ -167,29 +168,29 @@ def test_force_mode_srv(self):
167168 header .stamp .nsecs = 0
168169 frame_stamp = PoseStamped (header , task_frame_pose )
169170 compliance = [0 ,0 ,1 ,0 ,0 ,1 ]
170- wrench_vec = Wrench (Vector3 (0 ,0 ,1 ),Vector3 (0 ,0 ,1 ))
171- wrench_stamp = WrenchStamped (header ,wrench_vec )
172- type_spec = 2
173- limits = Twist (Vector3 (0.1 ,0.1 ,0.1 ), Vector3 (0.1 ,0.1 ,0.1 ))
174- limits_stamp = TwistStamped (header , limits )
171+ wrench = Wrench (Vector3 (0 ,0 ,1 ),Vector3 (0 ,0 ,1 ))
172+ type_spec = req .NO_TRANSFORM
173+ speed_limits = Twist (Vector3 (0.1 ,0.1 ,0.1 ), Vector3 (0.1 ,0.1 ,0.1 ))
174+ deviation_limits = [0.1 , 0.1 , 0.1 , 0.1 , 0.1 , 0.1 ]
175175 damping_factor = 0.8
176176 gain_scale = 0.8
177- req = SetForceModeRequest ()
177+
178178 req .task_frame = frame_stamp
179179 req .selection_vector_x = compliance [0 ]
180180 req .selection_vector_y = compliance [1 ]
181181 req .selection_vector_z = compliance [2 ]
182182 req .selection_vector_rx = compliance [3 ]
183183 req .selection_vector_ry = compliance [4 ]
184184 req .selection_vector_rz = compliance [5 ]
185- req .wrench = wrench_stamp
185+ req .wrench = wrench
186186 req .type = type_spec
187- req .limits = limits_stamp
187+ req .speed_limits = speed_limits
188+ req .deviation_limits = deviation_limits
188189 req .damping_factor = damping_factor
189190 req .gain_scaling = gain_scale
190191 res = self .start_force_mode_srv .call (req )
191192 self .assertEqual (res .success , True )
192- res = self .end_force_mode_srv .call (TriggerRequest ())
193+ res = self .stop_force_mode_srv .call (TriggerRequest ())
193194 self .assertEqual (res .success , True )
194195
195196
0 commit comments