2727# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
2828# POSSIBILITY OF SUCH DAMAGE.
2929
30- import copy
31- import logging
3230import os
3331import sys
3432import time
5250 Quaternion ,
5351 Point ,
5452 Twist ,
55- WrenchStamped ,
5653 Wrench ,
5754 Vector3 ,
5855)
59- from ur_msgs .srv import SetForceMode
6056
6157sys .path .append (os .path .dirname (__file__ ))
6258from test_common import ( # noqa: E402
63- ActionInterface ,
6459 ControllerManagerInterface ,
6560 DashboardInterface ,
6661 ForceModeInterface ,
6762 IoStatusInterface ,
6863 ConfigurationInterface ,
6964 generate_driver_test_description ,
70- ROBOT_JOINTS ,
7165)
7266
7367TIMEOUT_EXECUTE_TRAJECTORY = 30
@@ -106,9 +100,7 @@ def init_robot(self):
106100 def setUp (self ):
107101 self ._dashboard_interface .start_robot ()
108102 time .sleep (1 )
109- self .assertTrue (
110- self ._io_status_controller_interface .resend_robot_program ().success
111- )
103+ self .assertTrue (self ._io_status_controller_interface .resend_robot_program ().success )
112104 self .tf_buffer = Buffer ()
113105 self .tf_listener = TransformListener (self .tf_buffer , self .node )
114106
@@ -155,7 +147,7 @@ def test_force_mode_controller(self, tf_prefix):
155147 speed_limits = Twist ()
156148 speed_limits .linear = Vector3 (x = 0.0 , y = 0.0 , z = 1.0 )
157149 speed_limits .angular = Vector3 (x = 0.0 , y = 0.0 , z = 1.0 )
158- deviation_limits = [1.0 , 1.0 , 1.0 , 0.5 , 1.0 , 1.0 , 1.0 ]
150+ deviation_limits = [1.0 , 1.0 , 1.0 , 1.0 , 1.0 , 1.0 ]
159151
160152 # specify damping and gain scaling
161153 damping_factor = 0.1
@@ -168,7 +160,7 @@ def test_force_mode_controller(self, tf_prefix):
168160 trans_before = self .tf_buffer .lookup_transform (
169161 tf_prefix + "base" , tf_prefix + "tool0" , rclpy .time .Time ()
170162 )
171- except TransformException as ex :
163+ except TransformException :
172164 pass
173165
174166 # Send request to controller
@@ -199,17 +191,15 @@ def test_force_mode_controller(self, tf_prefix):
199191 trans_after = self .tf_buffer .lookup_transform (
200192 tf_prefix + "base" , tf_prefix + "tool0" , timepoint
201193 )
202- except TransformException as ex :
194+ except TransformException :
203195 pass
204196
205197 # task frame and wrench determines the expected motion
206198 # In the example we used
207199 # - a task frame rotated pi/2 deg around the base frame's x axis
208200 # - a wrench with a positive z component for the force
209201 # => we should expect a motion in negative y of the base frame
210- self .assertTrue (
211- trans_after .transform .translation .y < trans_before .transform .translation .y
212- )
202+ self .assertTrue (trans_after .transform .translation .y < trans_before .transform .translation .y )
213203 self .assertAlmostEqual (
214204 trans_after .transform .translation .x ,
215205 trans_before .transform .translation .x ,
0 commit comments