@@ -6884,6 +6884,32 @@ def REQUIRE_LOCATION_FOR_ARMING(self):
6884
6884
self .context_pop ()
6885
6885
self .reboot_sitl ()
6886
6886
6887
+ def GetMessageInterval (self ):
6888
+ '''check that the two methods for requesting a MESSAGE_INTERVAL message are equivalent'''
6889
+ target_msg = mavutil .mavlink .MAVLINK_MSG_ID_HOME_POSITION
6890
+ old_cmd = (mavutil .mavlink .MAV_CMD_GET_MESSAGE_INTERVAL , target_msg , 0 )
6891
+ new_cmd = (mavutil .mavlink .MAV_CMD_REQUEST_MESSAGE , mavutil .mavlink .MAVLINK_MSG_ID_MESSAGE_INTERVAL , target_msg )
6892
+
6893
+ interval_us = None
6894
+
6895
+ for run_command in self .run_cmd , self .run_cmd_int :
6896
+ for cmd in old_cmd , new_cmd :
6897
+ cmd_id , p1 , p2 = cmd
6898
+
6899
+ self .context_collect ("MESSAGE_INTERVAL" )
6900
+ run_command (cmd_id , p1 = p1 , p2 = p2 )
6901
+ m = self .assert_receive_message ('MESSAGE_INTERVAL' , timeout = 1 , check_context = True )
6902
+ self .context_clear_collection ("MESSAGE_INTERVAL" )
6903
+
6904
+ if m .message_id != target_msg :
6905
+ raise NotAchievedException (f"Unexpected ID in MESSAGE_INTERVAL (want={ target_msg } , got={ m .message_id } )" )
6906
+
6907
+ if interval_us is None :
6908
+ interval_us = m .interval_us
6909
+
6910
+ if m .interval_us != interval_us :
6911
+ raise NotAchievedException (f"Unexpected interval_us (want={ interval_us } , got={ m .interval_us } )" )
6912
+
6887
6913
def tests (self ):
6888
6914
'''return list of all tests'''
6889
6915
ret = super (AutoTestRover , self ).tests ()
@@ -6984,6 +7010,7 @@ def tests(self):
6984
7010
self .JammingSimulation ,
6985
7011
self .BatteryInvalid ,
6986
7012
self .REQUIRE_LOCATION_FOR_ARMING ,
7013
+ self .GetMessageInterval ,
6987
7014
])
6988
7015
return ret
6989
7016
0 commit comments