Skip to content

Commit b4d4438

Browse files
authored
Remove wrong seq entry (#1488)
I don't know why it ended up there in the first place.
1 parent e5cfa88 commit b4d4438

File tree

1 file changed

+6
-6
lines changed

1 file changed

+6
-6
lines changed

ur_robot_driver/test/integration_test_force_mode.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -156,7 +156,7 @@ def run_force_mode(self, tf_prefix):
156156
task_frame_pose = Pose()
157157
task_frame_pose.position = point
158158
task_frame_pose.orientation = orientation
159-
header = std_msgs.msg.Header(seq=1, frame_id=tf_prefix + "tool0_controller")
159+
header = std_msgs.msg.Header(frame_id=tf_prefix + "tool0_controller")
160160
frame_stamp = PoseStamped()
161161
frame_stamp.header = header
162162
frame_stamp.pose = task_frame_pose
@@ -359,7 +359,7 @@ def test_illegal_force_mode_types(self, tf_prefix):
359359
task_frame_pose = Pose()
360360
task_frame_pose.position = point
361361
task_frame_pose.orientation = orientation
362-
header = std_msgs.msg.Header(seq=1, frame_id=tf_prefix + "base")
362+
header = std_msgs.msg.Header(frame_id=tf_prefix + "base")
363363
header.stamp.sec = int(time.time()) + 1
364364
header.stamp.nanosec = 0
365365
frame_stamp = PoseStamped()
@@ -401,7 +401,7 @@ def test_illegal_task_frame(self, tf_prefix):
401401
task_frame_pose = Pose()
402402
task_frame_pose.position = point
403403
task_frame_pose.orientation = orientation
404-
header = std_msgs.msg.Header(seq=1, frame_id=tf_prefix + "base")
404+
header = std_msgs.msg.Header(frame_id=tf_prefix + "base")
405405
header.stamp.sec = int(time.time()) + 1
406406
header.stamp.nanosec = 0
407407
frame_stamp = PoseStamped()
@@ -443,7 +443,7 @@ def test_start_force_mode_on_inactive_controller_fails(self, tf_prefix):
443443
task_frame_pose = Pose()
444444
task_frame_pose.position = point
445445
task_frame_pose.orientation = orientation
446-
header = std_msgs.msg.Header(seq=1, frame_id=tf_prefix + "base")
446+
header = std_msgs.msg.Header(frame_id=tf_prefix + "base")
447447
header.stamp.sec = int(time.time()) + 1
448448
header.stamp.nanosec = 0
449449
frame_stamp = PoseStamped()
@@ -476,7 +476,7 @@ def test_deactivating_controller_stops_force_mode(self, tf_prefix):
476476
task_frame_pose = Pose()
477477
task_frame_pose.position = point
478478
task_frame_pose.orientation = orientation
479-
header = std_msgs.msg.Header(seq=1, frame_id=tf_prefix + "base")
479+
header = std_msgs.msg.Header(frame_id=tf_prefix + "base")
480480
header.stamp.sec = int(time.time()) + 1
481481
header.stamp.nanosec = 0
482482
frame_stamp = PoseStamped()
@@ -570,7 +570,7 @@ def test_params_out_of_range_fails(self, tf_prefix):
570570
task_frame_pose = Pose()
571571
task_frame_pose.position = point
572572
task_frame_pose.orientation = orientation
573-
header = std_msgs.msg.Header(seq=1, frame_id=tf_prefix + "base")
573+
header = std_msgs.msg.Header(frame_id=tf_prefix + "base")
574574
header.stamp.sec = int(time.time()) + 1
575575
header.stamp.nanosec = 0
576576
frame_stamp = PoseStamped()

0 commit comments

Comments
 (0)