1
1
package com .o3dr .android .client .apis ;
2
2
3
3
import android .os .Bundle ;
4
- import android .support .annotation .IntDef ;
5
4
6
5
import com .o3dr .android .client .Drone ;
7
6
import com .o3dr .services .android .lib .coordinate .LatLong ;
8
7
import com .o3dr .services .android .lib .drone .attribute .AttributeType ;
9
8
import com .o3dr .services .android .lib .drone .attribute .error .CommandExecutionError ;
10
- import com .o3dr .services .android .lib .drone .property .Attitude ;
11
9
import com .o3dr .services .android .lib .drone .property .Gps ;
12
10
import com .o3dr .services .android .lib .model .AbstractCommandListener ;
13
11
import com .o3dr .services .android .lib .model .action .Action ;
14
12
15
- import java .lang .annotation .Retention ;
16
- import java .lang .annotation .RetentionPolicy ;
17
13
import java .util .concurrent .ConcurrentHashMap ;
18
14
19
15
import static com .o3dr .services .android .lib .drone .action .ControlActions .ACTION_DO_GUIDED_TAKEOFF ;
16
+ import static com .o3dr .services .android .lib .drone .action .ControlActions .ACTION_ENABLE_MANUAL_CONTROL ;
20
17
import static com .o3dr .services .android .lib .drone .action .ControlActions .ACTION_SEND_GUIDED_POINT ;
21
18
import static com .o3dr .services .android .lib .drone .action .ControlActions .ACTION_SET_CONDITION_YAW ;
22
19
import static com .o3dr .services .android .lib .drone .action .ControlActions .ACTION_SET_GUIDED_ALTITUDE ;
23
20
import static com .o3dr .services .android .lib .drone .action .ControlActions .ACTION_SET_VELOCITY ;
24
21
import static com .o3dr .services .android .lib .drone .action .ControlActions .EXTRA_ALTITUDE ;
22
+ import static com .o3dr .services .android .lib .drone .action .ControlActions .EXTRA_DO_ENABLE ;
25
23
import static com .o3dr .services .android .lib .drone .action .ControlActions .EXTRA_FORCE_GUIDED_POINT ;
26
24
import static com .o3dr .services .android .lib .drone .action .ControlActions .EXTRA_GUIDED_POINT ;
27
25
import static com .o3dr .services .android .lib .drone .action .ControlActions .EXTRA_VELOCITY_X ;
33
31
34
32
/**
35
33
* Provides access to the vehicle control functionality.
36
- *
34
+ * <p/>
37
35
* Use of this api might required the vehicle to be in a specific flight mode (i.e: GUIDED)
38
- *
36
+ * <p/>
39
37
* Created by Fredia Huya-Kouadio on 9/7/15.
40
38
*/
41
39
public class ControlApi extends Api {
42
40
43
- public static final int EARTH_NED_COORDINATE_FRAME = 0 ;
44
- public static final int VEHICLE_COORDINATE_FRAME = 1 ;
45
-
46
- @ IntDef ({EARTH_NED_COORDINATE_FRAME , VEHICLE_COORDINATE_FRAME })
47
- @ Retention (RetentionPolicy .SOURCE )
48
- public @interface CoordinateFrame {}
49
-
50
41
private static final ConcurrentHashMap <Drone , ControlApi > apiCache = new ConcurrentHashMap <>();
51
42
private static final Builder <ControlApi > apiBuilder = new Builder <ControlApi >() {
52
43
@ Override
@@ -57,16 +48,17 @@ public ControlApi build(Drone drone) {
57
48
58
49
/**
59
50
* Retrieves a control api instance.
51
+ *
60
52
* @param drone
61
53
* @return
62
54
*/
63
- public static ControlApi getApi (final Drone drone ){
55
+ public static ControlApi getApi (final Drone drone ) {
64
56
return getApi (drone , apiCache , apiBuilder );
65
57
}
66
58
67
59
private final Drone drone ;
68
60
69
- private ControlApi (Drone drone ){
61
+ private ControlApi (Drone drone ) {
70
62
this .drone = drone ;
71
63
}
72
64
@@ -123,13 +115,14 @@ public void climbTo(double altitude) {
123
115
124
116
/**
125
117
* Instructs the vehicle to turn to the specified target angle
118
+ *
126
119
* @param targetAngle Target angle in degrees [0-360], with 0 == north.
127
- * @param turnRate Turning rate normalized to the range [-1.0f, 1.0f]. Positive values for clockwise turns, and negative values for counter-clockwise turns.
128
- * @param isRelative True is the target angle is relative to the current vehicle attitude, false otherwise if it's absolute.
129
- * @param listener Register a callback to receive update of the command execution state.
120
+ * @param turnRate Turning rate normalized to the range [-1.0f, 1.0f]. Positive values for clockwise turns, and negative values for counter-clockwise turns.
121
+ * @param isRelative True is the target angle is relative to the current vehicle attitude, false otherwise if it's absolute.
122
+ * @param listener Register a callback to receive update of the command execution state.
130
123
*/
131
- public void turnTo (float targetAngle , float turnRate , boolean isRelative , AbstractCommandListener listener ){
132
- if (!isWithinBounds (targetAngle , 0 , 360 ) || !isWithinBounds (turnRate , -1.0f , 1.0f )){
124
+ public void turnTo (float targetAngle , float turnRate , boolean isRelative , AbstractCommandListener listener ) {
125
+ if (!isWithinBounds (targetAngle , 0 , 360 ) || !isWithinBounds (turnRate , -1.0f , 1.0f )) {
133
126
postErrorEvent (CommandExecutionError .COMMAND_FAILED , listener );
134
127
return ;
135
128
}
@@ -141,7 +134,21 @@ public void turnTo(float targetAngle, float turnRate, boolean isRelative, Abstra
141
134
drone .performAsyncActionOnDroneThread (new Action (ACTION_SET_CONDITION_YAW , params ), listener );
142
135
}
143
136
144
- private void moveAtVelocity (float vx , float vy , float vz , AbstractCommandListener listener ){
137
+ /**
138
+ * Move the vehicle along the specified normalized velocity vector.
139
+ *
140
+ * @param vx x velocity normalized to the range [-1.0f, 1.0f]. Generally correspond to the pitch of the vehicle.
141
+ * @param vy y velocity normalized to the range [-1.0f, 1.0f]. Generally correspond to the roll of the vehicle.
142
+ * @param vz z velocity normalized to the range [-1.0f, 1.0f]. Generally correspond to the thrust of the vehicle.
143
+ * @param listener Register a callback to receive update of the command execution state.
144
+ * @since 2.6.9
145
+ */
146
+ public void manualControl (float vx , float vy , float vz , AbstractCommandListener listener ) {
147
+ if (!isWithinBounds (vx , -1f , 1f ) || !isWithinBounds (vy , -1f , 1f ) || !isWithinBounds (vz , -1f , 1f )) {
148
+ postErrorEvent (CommandExecutionError .COMMAND_FAILED , listener );
149
+ return ;
150
+ }
151
+
145
152
Bundle params = new Bundle ();
146
153
params .putFloat (EXTRA_VELOCITY_X , vx );
147
154
params .putFloat (EXTRA_VELOCITY_Y , vy );
@@ -150,41 +157,63 @@ private void moveAtVelocity(float vx, float vy, float vz, AbstractCommandListene
150
157
}
151
158
152
159
/**
153
- * Move the vehicle along the specified velocity vector.
154
- *
155
- * @param referenceFrame Reference frame to use. Can be one of
156
- * {@link #EARTH_NED_COORDINATE_FRAME},
157
- * {@link #VEHICLE_COORDINATE_FRAME}
160
+ * [Dis|En]able manual control on the vehicle.
161
+ * The result of the action will be conveyed through the passed listener.
158
162
*
159
- * @param vx x velocity normalized to the range [-1.0f, 1.0f].
160
- * @param vy y velocity normalized to the range [-1.0f, 1.0f].
161
- * @param vz z velocity normalized to the range [-1.0f, 1.0f].
162
- * @param listener Register a callback to receive update of the command execution state.
163
+ * @param enable True to enable manual control, false to disable.
164
+ * @param listener Register a callback to receive the result of the operation.
165
+ * @since 2.6.9
163
166
*/
164
- public void moveAtVelocity (@ CoordinateFrame int referenceFrame , float vx , float vy , float vz , AbstractCommandListener listener ){
165
- if (!isWithinBounds (vx , -1f , 1f ) || !isWithinBounds (vy , -1f , 1f ) || !isWithinBounds (vz , -1f , 1f )){
166
- postErrorEvent (CommandExecutionError .COMMAND_FAILED , listener );
167
- return ;
168
- }
169
-
170
- float projectedX = vx ;
171
- float projectedY = vy ;
172
-
173
- if (referenceFrame == VEHICLE_COORDINATE_FRAME ) {
174
- Attitude attitude = drone .getAttribute (AttributeType .ATTITUDE );
175
- double attitudeInRad = Math .toRadians (attitude .getYaw ());
167
+ public void enableManualControl (final boolean enable , final ManualControlStateListener listener ) {
168
+ AbstractCommandListener listenerWrapper = listener == null ? null
169
+ : new AbstractCommandListener () {
170
+ @ Override
171
+ public void onSuccess () {
172
+ if (enable ) {
173
+ listener .onManualControlEnabled ();
174
+ } else {
175
+ listener .onManualControlDisabled ();
176
+ }
177
+ }
176
178
177
- final double cosAttitude = Math .cos (attitudeInRad );
178
- final double sinAttitude = Math .sin (attitudeInRad );
179
+ @ Override
180
+ public void onError (int executionError ) {
181
+ if (enable ) {
182
+ listener .onManualControlDisabled ();
183
+ }
184
+ }
179
185
180
- projectedX = (float ) (vx * cosAttitude ) - (float ) (vy * sinAttitude );
181
- projectedY = (float ) (vx * sinAttitude ) + (float ) (vy * cosAttitude );
182
- }
186
+ @ Override
187
+ public void onTimeout () {
188
+ if (enable ) {
189
+ listener .onManualControlDisabled ();
190
+ }
191
+ }
192
+ };
183
193
184
- moveAtVelocity (projectedX , projectedY , vz , listener );
194
+ Bundle params = new Bundle ();
195
+ params .putBoolean (EXTRA_DO_ENABLE , enable );
196
+ drone .performAsyncActionOnDroneThread (new Action (ACTION_ENABLE_MANUAL_CONTROL , params ), listenerWrapper );
185
197
}
186
198
187
- private static boolean isWithinBounds (float value , float lowerBound , float upperBound ){
199
+ private static boolean isWithinBounds (float value , float lowerBound , float upperBound ) {
188
200
return value <= upperBound && value >= lowerBound ;
189
201
}
202
+
203
+ /**
204
+ * Used to monitor the state of manual control for the vehicle.
205
+ *
206
+ * @since 2.6.9
207
+ */
208
+ public interface ManualControlStateListener {
209
+ /**
210
+ * Manual control is enabled on the vehicle.
211
+ */
212
+ void onManualControlEnabled ();
213
+
214
+ /**
215
+ * Manual control is disabled on the vehicle.
216
+ */
217
+ void onManualControlDisabled ();
218
+ }
190
219
}
0 commit comments