@@ -6945,6 +6945,61 @@ def SDPolyFence(self):
6945
6945
6946
6946
self .delay_sim_time (1000 )
6947
6947
6948
+ def convert_COMMAND_LONG_to_COMMAND_INT (self ):
6949
+ '''test the convert_COMMAND_LONG_to_COMMAND_INT function'''
6950
+ self .change_mode ('GUIDED' )
6951
+ self .wait_ready_to_arm ()
6952
+ self .run_cmd (
6953
+ mavutil .mavlink .MAV_CMD_DO_SET_HOME ,
6954
+ p5 = 0 , # lat
6955
+ p6 = 0 , # lng
6956
+ p7 = 0 , # alt
6957
+ )
6958
+
6959
+ self .run_cmd (
6960
+ mavutil .mavlink .MAV_CMD_DO_SET_HOME ,
6961
+ p5 = 10 , # lat
6962
+ p6 = 20 , # lng
6963
+ p7 = 30 , # alt
6964
+ )
6965
+ self .assert_home_position_at (10 , 20 , 30 )
6966
+
6967
+ self .progress ("Ensure NaN is bounced" )
6968
+ self .run_cmd (
6969
+ mavutil .mavlink .MAV_CMD_DO_SET_HOME ,
6970
+ p5 = float ("NaN" ), # lat
6971
+ p6 = 10 , # lng
6972
+ p7 = 10 , # alt
6973
+ want_result = mavutil .mavlink .MAV_RESULT_DENIED ,
6974
+ )
6975
+
6976
+ self .progress ("Ensure INF is bounced" )
6977
+ self .run_cmd (
6978
+ mavutil .mavlink .MAV_CMD_DO_SET_HOME ,
6979
+ p5 = float ("Inf" ), # lat
6980
+ p6 = 10 , # lng
6981
+ p7 = 10 , # alt
6982
+ want_result = mavutil .mavlink .MAV_RESULT_DENIED ,
6983
+ )
6984
+
6985
+ self .progress ("Ensure OOB lat is bounced" )
6986
+ self .run_cmd (
6987
+ mavutil .mavlink .MAV_CMD_DO_SET_HOME ,
6988
+ p5 = 91 , # lat
6989
+ p6 = 10 , # lng
6990
+ p7 = 10 , # alt
6991
+ want_result = mavutil .mavlink .MAV_RESULT_DENIED ,
6992
+ )
6993
+
6994
+ self .progress ("Ensure OOB lng is bounced" )
6995
+ self .run_cmd (
6996
+ mavutil .mavlink .MAV_CMD_DO_SET_HOME ,
6997
+ p5 = 10 , # lat
6998
+ p6 = 190 , # lng
6999
+ p7 = 10 , # alt
7000
+ want_result = mavutil .mavlink .MAV_RESULT_DENIED ,
7001
+ )
7002
+
6948
7003
def tests (self ):
6949
7004
'''return list of all tests'''
6950
7005
ret = super (AutoTestRover , self ).tests ()
@@ -7043,6 +7098,7 @@ def tests(self):
7043
7098
self .ClearMission ,
7044
7099
self .JammingSimulation ,
7045
7100
self .BatteryInvalid ,
7101
+ self .convert_COMMAND_LONG_to_COMMAND_INT ,
7046
7102
])
7047
7103
return ret
7048
7104
0 commit comments