@@ -34,20 +34,26 @@ def arm(self, force: bool = False) -> Response:
3434 Returns:
3535 Response: The response from the arm command
3636 """
37+ return_data = {
38+ "was_disarming" : False ,
39+ "was_force" : force ,
40+ }
41+
3742 if self .drone .armed :
38- return {"success" : False , "message" : "Already armed" }
43+ return {"success" : False , "message" : "Already armed" , "data" : return_data }
3944
4045 if not self .drone .reserve_message_type ("COMMAND_ACK" , self .controller_id ):
4146 return {
4247 "success" : False ,
4348 "message" : "Could not reserve COMMAND_ACK messages" ,
49+ "data" : return_data ,
4450 }
4551
4652 try :
4753 self .drone .sendCommand (
4854 mavutil .mavlink .MAV_CMD_COMPONENT_ARM_DISARM ,
4955 param1 = 1 , # 0=disarm, 1=arm
50- param2 = 2989 if force else 0 , # force arm/disarm
56+ param2 = 21196 if force else 0 , # force arm/disarm
5157 )
5258
5359 response = self .drone .wait_for_message (
@@ -63,19 +69,28 @@ def arm(self, force: bool = False) -> Response:
6369 while not self .drone .armed :
6470 time .sleep (0.05 )
6571 self .drone .logger .debug ("ARMED" )
66- return {"success" : True , "message" : "Armed successfully" }
72+ return {
73+ "success" : True ,
74+ "message" : "Armed successfully" ,
75+ "data" : return_data ,
76+ }
6777 else :
6878 self .drone .logger .debug ("Arming failed" )
6979 return {
7080 "success" : False ,
7181 "message" : "Could not arm, command not accepted" ,
82+ "data" : return_data ,
7283 }
7384
7485 except Exception as e :
7586 self .drone .logger .error (e , exc_info = True )
7687 if self .drone .droneErrorCb :
7788 self .drone .droneErrorCb (str (e ))
78- return {"success" : False , "message" : "Could not arm, serial exception" }
89+ return {
90+ "success" : False ,
91+ "message" : "Could not arm, serial exception" ,
92+ "data" : return_data ,
93+ }
7994 finally :
8095 self .drone .release_message_type ("COMMAND_ACK" , self .controller_id )
8196
@@ -90,20 +105,30 @@ def disarm(self, force: bool = False) -> Response:
90105 Returns:
91106 Response: The response from the disarm command
92107 """
108+ return_data = {
109+ "was_disarming" : True ,
110+ "was_force" : force ,
111+ }
112+
93113 if not self .drone .armed :
94- return {"success" : False , "message" : "Already disarmed" }
114+ return {
115+ "success" : False ,
116+ "message" : "Already disarmed" ,
117+ "data" : return_data ,
118+ }
95119
96120 if not self .drone .reserve_message_type ("COMMAND_ACK" , self .controller_id ):
97121 return {
98122 "success" : False ,
99123 "message" : "Could not reserve COMMAND_ACK messages" ,
124+ "data" : return_data ,
100125 }
101126
102127 try :
103128 self .drone .sendCommand (
104129 mavutil .mavlink .MAV_CMD_COMPONENT_ARM_DISARM ,
105130 param1 = 0 , # 0=disarm, 1=arm
106- param2 = 2989 if force else 0 , # force arm/disarm
131+ param2 = 21196 if force else 0 , # force arm/disarm
107132 )
108133
109134 response = self .drone .wait_for_message (
@@ -119,18 +144,27 @@ def disarm(self, force: bool = False) -> Response:
119144 while self .drone .armed :
120145 time .sleep (0.05 )
121146 self .drone .logger .debug ("DISARMED" )
122- return {"success" : True , "message" : "Disarmed successfully" }
147+ return {
148+ "success" : True ,
149+ "message" : "Disarmed successfully" ,
150+ "data" : return_data ,
151+ }
123152 else :
124153 self .drone .logger .debug ("Could not disarm, command not accepted" )
125154 return {
126155 "success" : False ,
127156 "message" : "Could not disarm, command not accepted" ,
157+ "data" : return_data ,
128158 }
129159
130160 except Exception as e :
131161 self .drone .logger .error (e , exc_info = True )
132162 if self .drone .droneErrorCb :
133163 self .drone .droneErrorCb (str (e ))
134- return {"success" : False , "message" : "Could not disarm, serial exception" }
164+ return {
165+ "success" : False ,
166+ "message" : "Could not disarm, serial exception" ,
167+ "data" : return_data ,
168+ }
135169 finally :
136170 self .drone .release_message_type ("COMMAND_ACK" , self .controller_id )
0 commit comments