File tree 2 files changed +27
-0
lines changed
2 files changed +27
-0
lines changed Original file line number Diff line number Diff line change @@ -19,4 +19,25 @@ bool AP_ExternalControl_Plane::set_global_position(const Location& loc)
19
19
return plane.set_target_location (loc);
20
20
}
21
21
22
+ /*
23
+ Sets the target global position for a loiter point.
24
+ */
25
+ bool AP_ExternalControl_Plane::set_airspeed (const float airspeed)
26
+ {
27
+ #if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
28
+ // command is only valid in guided mode
29
+ if (plane.control_mode != &plane.mode_guided ) {
30
+ return false ;
31
+ }
32
+
33
+ if (airspeed > plane.aparm .airspeed_max || airspeed < plane.aparm .airspeed_min ) {
34
+ return false ;
35
+ }
36
+ plane.guided_state .target_airspeed_cm = airspeed * 100 ;
37
+ return true ;
38
+ #else
39
+ return false ;
40
+ #endif
41
+ }
42
+
22
43
#endif // AP_EXTERNAL_CONTROL_ENABLED
Original file line number Diff line number Diff line change @@ -16,6 +16,12 @@ class AP_ExternalControl_Plane : public AP_ExternalControl {
16
16
Sets the target global position for a loiter point.
17
17
*/
18
18
bool set_global_position (const Location& loc) override WARN_IF_UNUSED;
19
+
20
+ /*
21
+ Sets the target airspeed.
22
+ */
23
+ bool set_airspeed (const float airspeed) override WARN_IF_UNUSED;
24
+
19
25
};
20
26
21
27
#endif // AP_EXTERNAL_CONTROL_ENABLED
You can’t perform that action at this time.
0 commit comments