Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_ExternalControl/AP_ExternalControl.h
9383 views
1
/*
2
external control library for MAVLink, DDS and scripting
3
*/
4
5
#pragma once
6
7
#include "AP_ExternalControl_config.h"
8
9
#if AP_EXTERNAL_CONTROL_ENABLED
10
11
#include <AP_Arming/AP_Arming.h>
12
#include <AP_Common/Location.h>
13
#include <AP_Math/AP_Math.h>
14
15
class AP_ExternalControl
16
{
17
public:
18
19
AP_ExternalControl();
20
21
/*
22
Sets the target airspeed.
23
*/
24
virtual bool set_airspeed(const float airspeed) WARN_IF_UNUSED {
25
return false;
26
}
27
/*
28
Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw.
29
Velocity is in earth frame, NED [m/s].
30
Yaw is in earth frame, NED [rad/s].
31
*/
32
virtual bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) WARN_IF_UNUSED {
33
return false;
34
}
35
36
/*
37
Sets the target global position with standard guided mode behavior.
38
*/
39
virtual bool set_global_position(const Location& loc) WARN_IF_UNUSED {
40
return false;
41
}
42
43
/*
44
Arm the vehicle
45
*/
46
virtual bool arm(AP_Arming::Method method, bool do_arming_checks) WARN_IF_UNUSED;
47
48
/*
49
Disarm the vehicle
50
*/
51
virtual bool disarm(AP_Arming::Method method, bool do_disarm_checks) WARN_IF_UNUSED;
52
53
static AP_ExternalControl *get_singleton(void) WARN_IF_UNUSED {
54
return singleton;
55
}
56
protected:
57
~AP_ExternalControl() {}
58
59
private:
60
static AP_ExternalControl *singleton;
61
};
62
63
64
namespace AP
65
{
66
AP_ExternalControl *externalcontrol();
67
};
68
69
#endif // AP_EXTERNAL_CONTROL_ENABLED
70
71