mirror of https://github.com/ArduPilot/ardupilot
44 lines
815 B
C
44 lines
815 B
C
|
/*
|
||
|
external control library for MAVLink, DDS and scripting
|
||
|
*/
|
||
|
|
||
|
#pragma once
|
||
|
|
||
|
#include "AP_ExternalControl_config.h"
|
||
|
|
||
|
#if AP_EXTERNAL_CONTROL_ENABLED
|
||
|
|
||
|
#include <AP_Math/AP_Math.h>
|
||
|
|
||
|
class AP_ExternalControl
|
||
|
{
|
||
|
public:
|
||
|
|
||
|
AP_ExternalControl();
|
||
|
/*
|
||
|
Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw.
|
||
|
Velocity is in earth frame, NED [m/s].
|
||
|
Yaw is in earth frame, NED [rad/s].
|
||
|
*/
|
||
|
virtual bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads)
|
||
|
{
|
||
|
return false;
|
||
|
}
|
||
|
|
||
|
static AP_ExternalControl *get_singleton(void)
|
||
|
{
|
||
|
return singleton;
|
||
|
}
|
||
|
|
||
|
private:
|
||
|
static AP_ExternalControl *singleton;
|
||
|
};
|
||
|
|
||
|
|
||
|
namespace AP
|
||
|
{
|
||
|
AP_ExternalControl *externalcontrol();
|
||
|
};
|
||
|
|
||
|
#endif // AP_EXTERNAL_CONTROL_ENABLED
|