@@ -34,24 +34,19 @@ 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 {
39- "success" : False ,
40- "message" : "Already armed" ,
41- "data" : {
42- "was_disarming" : False ,
43- "was_force" : force ,
44- },
45- }
43+ return {"success" : False , "message" : "Already armed" , "data" : return_data }
4644
4745 if not self .drone .reserve_message_type ("COMMAND_ACK" , self .controller_id ):
4846 return {
4947 "success" : False ,
5048 "message" : "Could not reserve COMMAND_ACK messages" ,
51- "data" : {
52- "was_disarming" : False ,
53- "was_force" : force ,
54- },
49+ "data" : return_data ,
5550 }
5651
5752 try :
@@ -75,22 +70,16 @@ def arm(self, force: bool = False) -> Response:
7570 time .sleep (0.05 )
7671 self .drone .logger .debug ("ARMED" )
7772 return {
78- "success" : False ,
73+ "success" : True ,
7974 "message" : "Armed successfully" ,
80- "data" : {
81- "was_disarming" : False ,
82- "was_force" : force ,
83- },
75+ "data" : return_data ,
8476 }
8577 else :
8678 self .drone .logger .debug ("Arming failed" )
8779 return {
8880 "success" : False ,
8981 "message" : "Could not arm, command not accepted" ,
90- "data" : {
91- "was_disarming" : False ,
92- "was_force" : force ,
93- },
82+ "data" : return_data ,
9483 }
9584
9685 except Exception as e :
@@ -100,10 +89,7 @@ def arm(self, force: bool = False) -> Response:
10089 return {
10190 "success" : False ,
10291 "message" : "Could not arm, serial exception" ,
103- "data" : {
104- "was_disarming" : False ,
105- "was_force" : force ,
106- },
92+ "data" : return_data ,
10793 }
10894 finally :
10995 self .drone .release_message_type ("COMMAND_ACK" , self .controller_id )
@@ -119,24 +105,23 @@ def disarm(self, force: bool = False) -> Response:
119105 Returns:
120106 Response: The response from the disarm command
121107 """
108+ return_data = {
109+ "was_disarming" : True ,
110+ "was_force" : force ,
111+ }
112+
122113 if not self .drone .armed :
123114 return {
124115 "success" : False ,
125116 "message" : "Already disarmed" ,
126- "data" : {
127- "was_disarming" : True ,
128- "was_force" : force ,
129- },
117+ "data" : return_data ,
130118 }
131119
132120 if not self .drone .reserve_message_type ("COMMAND_ACK" , self .controller_id ):
133121 return {
134122 "success" : False ,
135123 "message" : "Could not reserve COMMAND_ACK messages" ,
136- "data" : {
137- "was_disarming" : True ,
138- "was_force" : force ,
139- },
124+ "data" : return_data ,
140125 }
141126
142127 try :
@@ -162,26 +147,24 @@ def disarm(self, force: bool = False) -> Response:
162147 return {
163148 "success" : True ,
164149 "message" : "Disarmed successfully" ,
165- "data" : {
166- "was_disarming" : True ,
167- "was_force" : force ,
168- },
150+ "data" : return_data ,
169151 }
170152 else :
171153 self .drone .logger .debug ("Could not disarm, command not accepted" )
172154 return {
173155 "success" : False ,
174156 "message" : "Could not disarm, command not accepted" ,
175- "data" : {
176- "was_disarming" : True ,
177- "was_force" : force ,
178- },
157+ "data" : return_data ,
179158 }
180159
181160 except Exception as e :
182161 self .drone .logger .error (e , exc_info = True )
183162 if self .drone .droneErrorCb :
184163 self .drone .droneErrorCb (str (e ))
185- 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+ }
186169 finally :
187170 self .drone .release_message_type ("COMMAND_ACK" , self .controller_id )
0 commit comments