15
15
from std_srvs .srv import Trigger , TriggerRequest
16
16
import tf
17
17
from trajectory_msgs .msg import JointTrajectoryPoint
18
- from ur_msgs .srv import SetIO , SetIORequest
18
+ from geometry_msgs .msg import Pose , PoseStamped , Quaternion , Point , WrenchStamped , TwistStamped , Wrench , Twist , Vector3
19
+ from ur_msgs .srv import SetIO , SetIORequest , SetForceModeRequest , SetForceMode
19
20
from ur_msgs .msg import IOStates
20
21
21
22
from cartesian_control_msgs .msg import (
@@ -119,6 +120,20 @@ def init_robot(self):
119
120
"Could not reach resend_robot_program service. Make sure that the driver is "
120
121
"actually running in headless mode."
121
122
" Msg: {}" .format (err ))
123
+
124
+ self .start_force_mode_srv = rospy .ServiceProxy ('/ur_hardware_interface/start_force_mode' , SetForceMode )
125
+ try :
126
+ self .start_force_mode_srv .wait_for_service (timeout )
127
+ except rospy .exceptions .ROSException as err :
128
+ self .fail ("Could not reach start force mode service. Make sure that the driver is actually running."
129
+ " Msg: {}" .format (err ))
130
+
131
+ self .end_force_mode_srv = rospy .ServiceProxy ('/ur_hardware_interface/end_force_mode' , Trigger )
132
+ try :
133
+ self .end_force_mode_srv .wait_for_service (timeout )
134
+ except rospy .exceptions .ROSException as err :
135
+ self .fail ("Could not reach end force mode service. Make sure that the driver is actually running."
136
+ " Msg: {}" .format (err ))
122
137
123
138
self .script_publisher = rospy .Publisher ("/ur_hardware_interface/script_command" , std_msgs .msg .String , queue_size = 1 )
124
139
self .tf_listener = tf .TransformListener ()
@@ -135,6 +150,40 @@ def set_robot_to_mode(self, target_mode):
135
150
self .set_mode_client .wait_for_result ()
136
151
return self .set_mode_client .get_result ().success
137
152
153
+ def test_force_mode_srv (self ):
154
+ point = Point (0.1 , 0.1 , 0.1 )
155
+ orientation = Quaternion (0 , 0 , 0 , 0 )
156
+ task_frame_pose = Pose (point , orientation )
157
+ header = std_msgs .msg .Header (seq = 1 , frame_id = "robot" )
158
+ header .stamp .secs = int (time .time ())+ 1
159
+ header .stamp .nsecs = 0
160
+ frame_stamp = PoseStamped (header , task_frame_pose )
161
+ compliance = [0 ,0 ,1 ,0 ,0 ,1 ]
162
+ wrench_vec = Wrench (Vector3 (0 ,0 ,1 ),Vector3 (0 ,0 ,1 ))
163
+ wrench_stamp = WrenchStamped (header ,wrench_vec )
164
+ type_spec = 2
165
+ limits = Twist (Vector3 (0.1 ,0.1 ,0.1 ), Vector3 (0.1 ,0.1 ,0.1 ))
166
+ limits_stamp = TwistStamped (header , limits )
167
+ damping_factor = 0.8
168
+ gain_scale = 0.8
169
+ req = SetForceModeRequest ()
170
+ req .task_frame = frame_stamp
171
+ req .selection_vector_x = compliance [0 ]
172
+ req .selection_vector_y = compliance [1 ]
173
+ req .selection_vector_z = compliance [2 ]
174
+ req .selection_vector_rx = compliance [3 ]
175
+ req .selection_vector_ry = compliance [4 ]
176
+ req .selection_vector_rz = compliance [5 ]
177
+ req .wrench = wrench_stamp
178
+ req .type = type_spec
179
+ req .limits = limits_stamp
180
+ req .damping_factor = damping_factor
181
+ req .gain_scaling = gain_scale
182
+ res = self .start_force_mode_srv .call (req )
183
+ self .assertEqual (res .success , True )
184
+ res = self .end_force_mode_srv .call (TriggerRequest ())
185
+ self .assertEqual (res .success , True )
186
+
138
187
139
188
def test_joint_trajectory_position_interface (self ):
140
189
"""Test robot movement"""
0 commit comments