Path: blob/master/ArduCopter/AP_ExternalControl_Copter.h
9564 views
/*1external control library for copter2*/3#pragma once45#include <AP_ExternalControl/AP_ExternalControl.h>67#if AP_EXTERNAL_CONTROL_ENABLED89class AP_ExternalControl_Copter : public AP_ExternalControl10{11public:12/*13Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw.14Velocity is in earth frame, NED [m/s].15Yaw is in earth frame, NED [rad/s].16*/17bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity_ned_ms, float yaw_rate_rads) override WARN_IF_UNUSED;1819/*20Sets the target global position for a loiter point.21*/22bool set_global_position(const Location& loc) override WARN_IF_UNUSED;23private:24/*25Return true if Copter is ready to handle external control data.26Currently checks mode and arm states.27*/28bool ready_for_external_control() WARN_IF_UNUSED;29};3031#endif // AP_EXTERNAL_CONTROL_ENABLED323334