@@ -4599,6 +4599,13 @@ def fly_guided_stop(self,
4599
4599
m .climb < climb_tolerance ):
4600
4600
break
4601
4601
4602
+ def send_set_position_target_global_int_loc (self , loc ):
4603
+ self .send_set_position_target_global_int (
4604
+ int (loc .lat * 1e7 ),
4605
+ int (loc .lng * 1e7 ),
4606
+ loc .alt
4607
+ )
4608
+
4602
4609
def send_set_position_target_global_int (self , lat , lon , alt ):
4603
4610
self .mav .mav .set_position_target_global_int_send (
4604
4611
0 , # timestamp
@@ -9576,6 +9583,67 @@ def MAV_CMD_CONDITION_YAW(self):
9576
9583
self ._MAV_CMD_CONDITION_YAW (self .run_cmd )
9577
9584
self .context_pop ()
9578
9585
9586
+ def MAV_CMD_CONDITION_YAW_heading_relative (self ):
9587
+ '''check relative-to-CoG yaw'''
9588
+ self .takeoff (10 , mode = 'GUIDED' )
9589
+ self .progress ("First make sure it cancelsan absolute yaw" )
9590
+ for heading in 30 , 60 :
9591
+ self .run_cmd_int (
9592
+ mavutil .mavlink .MAV_CMD_CONDITION_YAW ,
9593
+ p1 = heading , # target angle
9594
+ p2 = 360 , # degrees/second
9595
+ p3 = 1 , # -1 is counter-clockwise, 1 clockwise
9596
+ p4 = 0 , # 1 for relative, 0 for absolute
9597
+ )
9598
+ self .wait_heading (heading , minimum_duration = 5 )
9599
+
9600
+ here = self .mav .location ()
9601
+ t = self .offset_location_ne (here , 2000 , 0 )
9602
+
9603
+ self .do_reposition (t )
9604
+
9605
+ # reposition cancels the condition-yaw:
9606
+ self .run_cmd_int (
9607
+ mavutil .mavlink .MAV_CMD_CONDITION_YAW ,
9608
+ p1 = heading , # target angle
9609
+ p2 = 360 , # degrees/second
9610
+ p3 = 1 , # -1 is counter-clockwise, 1 clockwise
9611
+ p4 = 0 , # 1 for relative, 0 for absolute
9612
+ )
9613
+ self .wait_heading (60 , minimum_duration = 10 )
9614
+
9615
+ self .progress ("switch to yaw-looks-ahead" )
9616
+ self .run_cmd_int (
9617
+ mavutil .mavlink .MAV_CMD_CONDITION_YAW ,
9618
+ p1 = 0 , # target angle
9619
+ p2 = 360 , # degrees/second
9620
+ p3 = 1 , # -1 is counter-clockwise, 1 clockwise
9621
+ p4 = 2 , # 1 for relative, 0 for absolute, 2 for heading-relative
9622
+ )
9623
+ self .wait_heading (0 , minimum_duration = 10 )
9624
+
9625
+ # turn on preserve-yaw
9626
+ self .set_parameter ("GUID_OPTIONS" , 256 )
9627
+
9628
+ self .progress ("Now point 45-degrees to right of vehicle heading" )
9629
+ self .run_cmd_int (
9630
+ mavutil .mavlink .MAV_CMD_CONDITION_YAW ,
9631
+ p1 = 45 , # target angle
9632
+ p2 = 360 , # degrees/second
9633
+ p3 = 1 , # -1 is counter-clockwise, 1 clockwise
9634
+ p4 = 2 , # 1 for relative, 0 for absolute, 2 for heading-relative
9635
+ )
9636
+ self .wait_heading (45 , minimum_duration = 10 )
9637
+
9638
+ self .progress ("Heading east, checking yaw remains 45-degrees-to-heading" )
9639
+ here = self .mav .location ()
9640
+ t = self .offset_location_ne (here , 0 , 2000 )
9641
+
9642
+ self .send_set_position_target_global_int_loc (t )
9643
+ self .wait_heading (135 , minimum_duration = 10 )
9644
+
9645
+ self .do_RTL ()
9646
+
9579
9647
def GroundEffectCompensation_touchDownExpected (self ):
9580
9648
'''Test EKF's handling of touchdown-expected'''
9581
9649
self .zero_throttle ()
@@ -10415,6 +10483,7 @@ def tests1a(self):
10415
10483
self .NavDelay ,
10416
10484
self .GuidedSubModeChange ,
10417
10485
self .MAV_CMD_CONDITION_YAW ,
10486
+ self .MAV_CMD_CONDITION_YAW_heading_relative ,
10418
10487
self .LoiterToAlt ,
10419
10488
self .PayloadPlaceMission ,
10420
10489
self .PrecisionLoiterCompanion ,
0 commit comments