Path: blob/master/ArduCopter/AP_ExternalControl_Copter.cpp
9377 views
/*1external control library for copter2*/345#include "AP_ExternalControl_Copter.h"6#if AP_EXTERNAL_CONTROL_ENABLED78#include "Copter.h"910/*11set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw12velocity is in earth frame, NED, m/s13*/14bool AP_ExternalControl_Copter::set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity_ned_ms, float yaw_rate_rads)15{16if (!ready_for_external_control()) {17return false;18}19const float checked_yaw_rate_rad = isnan(yaw_rate_rads)? 0: yaw_rate_rads;2021// Copter velocity is positive if aircraft is moving up which is opposite the incoming NED frame.22copter.mode_guided.set_vel_NED_ms(linear_velocity_ned_ms, false, 0, !isnan(yaw_rate_rads), checked_yaw_rate_rad);23return true;24}2526bool AP_ExternalControl_Copter::set_global_position(const Location& loc)27{28// Check if copter is ready for external control and returns false if it is not.29if (!ready_for_external_control()) {30return false;31}32return copter.set_target_location(loc);33}3435bool AP_ExternalControl_Copter::ready_for_external_control()36{37return copter.flightmode->in_guided_mode() && copter.motors->armed();38}3940#endif // AP_EXTERNAL_CONTROL_ENABLED414243