Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduCopter/GCS_MAVLink_Copter.cpp
Views: 1798
#include "Copter.h"12#include "GCS_MAVLink_Copter.h"3#include <AP_RPM/AP_RPM_config.h>4#include <AP_EFI/AP_EFI_config.h>56MAV_TYPE GCS_Copter::frame_type() const7{8/*9for GCS don't give MAV_TYPE_GENERIC as the GCS would have no10information and won't display UIs such as flight mode11selection12*/13#if FRAME_CONFIG == HELI_FRAME14const MAV_TYPE mav_type_default = MAV_TYPE_HELICOPTER;15#else16const MAV_TYPE mav_type_default = MAV_TYPE_QUADROTOR;17#endif18if (copter.motors == nullptr) {19return mav_type_default;20}21MAV_TYPE mav_type = copter.motors->get_frame_mav_type();22if (mav_type == MAV_TYPE_GENERIC) {23mav_type = mav_type_default;24}25return mav_type;26}2728MAV_MODE GCS_MAVLINK_Copter::base_mode() const29{30uint8_t _base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;31// work out the base_mode. This value is not very useful32// for APM, but we calculate it as best we can so a generic33// MAVLink enabled ground station can work out something about34// what the MAV is up to. The actual bit values are highly35// ambiguous for most of the APM flight modes. In practice, you36// only get useful information from the custom_mode, which maps to37// the APM flight mode and has a well defined meaning in the38// ArduPlane documentation39if ((copter.pos_control != nullptr) && copter.pos_control->is_active_xy()) {40_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;41// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what42// APM does in any mode, as that is defined as "system finds its own goal43// positions", which APM does not currently do44}4546// all modes except INITIALISING have some form of manual47// override if stick mixing is enabled48_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;4950// we are armed if we are not initialising51if (copter.motors != nullptr && copter.motors->armed()) {52_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;53}5455// indicate we have set a custom mode56_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;5758return (MAV_MODE)_base_mode;59}6061uint32_t GCS_Copter::custom_mode() const62{63return (uint32_t)copter.flightmode->mode_number();64}6566MAV_STATE GCS_MAVLINK_Copter::vehicle_system_status() const67{68// set system as critical if any failsafe have triggered69if (copter.any_failsafe_triggered()) {70return MAV_STATE_CRITICAL;71}7273if (copter.ap.land_complete) {74return MAV_STATE_STANDBY;75}7677if (!copter.ap.initialised) {78return MAV_STATE_BOOT;79}8081return MAV_STATE_ACTIVE;82}838485void GCS_MAVLINK_Copter::send_attitude_target()86{87const Quaternion quat = copter.attitude_control->get_attitude_target_quat();88const Vector3f ang_vel = copter.attitude_control->get_attitude_target_ang_vel();89const float thrust = copter.attitude_control->get_throttle_in();9091const float quat_out[4] {quat.q1, quat.q2, quat.q3, quat.q4};9293// Note: When sending out the attitude_target info. we send out all of info. no matter the mavlink typemask94// This way we send out the maximum information that can be used by the sending control systems to adapt their generated trajectories95const uint16_t typemask = 0; // Ignore nothing9697mavlink_msg_attitude_target_send(98chan,99AP_HAL::millis(), // time since boot (ms)100typemask, // Bitmask that tells the system what control dimensions should be ignored by the vehicle101quat_out, // Attitude quaternion [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], unit-length102ang_vel.x, // roll rate (rad/s)103ang_vel.y, // pitch rate (rad/s)104ang_vel.z, // yaw rate (rad/s)105thrust); // Collective thrust, normalized to 0 .. 1106}107108void GCS_MAVLINK_Copter::send_position_target_global_int()109{110Location target;111if (!copter.flightmode->get_wp(target)) {112return;113}114115// convert altitude frame to AMSL (this may use the terrain database)116if (!target.change_alt_frame(Location::AltFrame::ABSOLUTE)) {117return;118}119static constexpr uint16_t POSITION_TARGET_TYPEMASK_LAST_BYTE = 0xF000;120static constexpr uint16_t TYPE_MASK = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |121POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE |122POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE;123mavlink_msg_position_target_global_int_send(124chan,125AP_HAL::millis(), // time_boot_ms126MAV_FRAME_GLOBAL, // targets are always global altitude127TYPE_MASK, // ignore everything except the x/y/z components128target.lat, // latitude as 1e7129target.lng, // longitude as 1e7130target.alt * 0.01f, // altitude is sent as a float1310.0f, // vx1320.0f, // vy1330.0f, // vz1340.0f, // afx1350.0f, // afy1360.0f, // afz1370.0f, // yaw1380.0f); // yaw_rate139}140141void GCS_MAVLINK_Copter::send_position_target_local_ned()142{143#if MODE_GUIDED_ENABLED144if (!copter.flightmode->in_guided_mode()) {145return;146}147148const ModeGuided::SubMode guided_mode = copter.mode_guided.submode();149Vector3f target_pos;150Vector3f target_vel;151Vector3f target_accel;152uint16_t type_mask = 0;153154switch (guided_mode) {155case ModeGuided::SubMode::Angle:156// we don't have a local target when in angle mode157return;158case ModeGuided::SubMode::TakeOff:159case ModeGuided::SubMode::WP:160case ModeGuided::SubMode::Pos:161type_mask = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |162POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE |163POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except position164target_pos = copter.mode_guided.get_target_pos().tofloat() * 0.01; // convert to metres165break;166case ModeGuided::SubMode::PosVelAccel:167type_mask = POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except position, velocity & acceleration168target_pos = copter.mode_guided.get_target_pos().tofloat() * 0.01; // convert to metres169target_vel = copter.mode_guided.get_target_vel() * 0.01f; // convert to metres/s170target_accel = copter.mode_guided.get_target_accel() * 0.01f; // convert to metres/s/s171break;172case ModeGuided::SubMode::VelAccel:173type_mask = POSITION_TARGET_TYPEMASK_X_IGNORE | POSITION_TARGET_TYPEMASK_Y_IGNORE | POSITION_TARGET_TYPEMASK_Z_IGNORE |174POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except velocity & acceleration175target_vel = copter.mode_guided.get_target_vel() * 0.01f; // convert to metres/s176target_accel = copter.mode_guided.get_target_accel() * 0.01f; // convert to metres/s/s177break;178case ModeGuided::SubMode::Accel:179type_mask = POSITION_TARGET_TYPEMASK_X_IGNORE | POSITION_TARGET_TYPEMASK_Y_IGNORE | POSITION_TARGET_TYPEMASK_Z_IGNORE |180POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |181POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except velocity & acceleration182target_accel = copter.mode_guided.get_target_accel() * 0.01f; // convert to metres/s/s183break;184}185186mavlink_msg_position_target_local_ned_send(187chan,188AP_HAL::millis(), // time boot ms189MAV_FRAME_LOCAL_NED,190type_mask,191target_pos.x, // x in metres192target_pos.y, // y in metres193-target_pos.z, // z in metres NED frame194target_vel.x, // vx in m/s195target_vel.y, // vy in m/s196-target_vel.z, // vz in m/s NED frame197target_accel.x, // afx in m/s/s198target_accel.y, // afy in m/s/s199-target_accel.z,// afz in m/s/s NED frame2000.0f, // yaw2010.0f); // yaw_rate202#endif203}204205void GCS_MAVLINK_Copter::send_nav_controller_output() const206{207if (!copter.ap.initialised) {208return;209}210const Vector3f &targets = copter.attitude_control->get_att_target_euler_cd();211const Mode *flightmode = copter.flightmode;212mavlink_msg_nav_controller_output_send(213chan,214targets.x * 1.0e-2f,215targets.y * 1.0e-2f,216targets.z * 1.0e-2f,217flightmode->wp_bearing() * 1.0e-2f,218MIN(flightmode->wp_distance() * 1.0e-2f, UINT16_MAX),219copter.pos_control->get_pos_error_z_cm() * 1.0e-2f,2200,221flightmode->crosstrack_error() * 1.0e-2f);222}223224float GCS_MAVLINK_Copter::vfr_hud_airspeed() const225{226#if AP_AIRSPEED_ENABLED227// airspeed sensors are best. While the AHRS airspeed_estimate228// will use an airspeed sensor, that value is constrained by the229// ground speed. When reporting we should send the true airspeed230// value if possible:231if (copter.airspeed.enabled() && copter.airspeed.healthy()) {232return copter.airspeed.get_airspeed();233}234#endif235236Vector3f airspeed_vec_bf;237if (AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {238// we are running the EKF3 wind estimation code which can give239// us an airspeed estimate240return airspeed_vec_bf.length();241}242return AP::gps().ground_speed();243}244245int16_t GCS_MAVLINK_Copter::vfr_hud_throttle() const246{247if (copter.motors == nullptr) {248return 0;249}250return (int16_t)(copter.motors->get_throttle() * 100);251}252253/*254send PID tuning message255*/256void GCS_MAVLINK_Copter::send_pid_tuning()257{258static const PID_TUNING_AXIS axes[] = {259PID_TUNING_ROLL,260PID_TUNING_PITCH,261PID_TUNING_YAW,262PID_TUNING_ACCZ263};264for (uint8_t i=0; i<ARRAY_SIZE(axes); i++) {265if (!(copter.g.gcs_pid_mask & (1<<(axes[i]-1)))) {266continue;267}268if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {269return;270}271const AP_PIDInfo *pid_info = nullptr;272switch (axes[i]) {273case PID_TUNING_ROLL:274pid_info = &copter.attitude_control->get_rate_roll_pid().get_pid_info();275break;276case PID_TUNING_PITCH:277pid_info = &copter.attitude_control->get_rate_pitch_pid().get_pid_info();278break;279case PID_TUNING_YAW:280pid_info = &copter.attitude_control->get_rate_yaw_pid().get_pid_info();281break;282case PID_TUNING_ACCZ:283pid_info = &copter.pos_control->get_accel_z_pid().get_pid_info();284break;285default:286continue;287}288if (pid_info != nullptr) {289mavlink_msg_pid_tuning_send(chan,290axes[i],291pid_info->target,292pid_info->actual,293pid_info->FF,294pid_info->P,295pid_info->I,296pid_info->D,297pid_info->slew_rate,298pid_info->Dmod);299}300}301}302303#if AP_WINCH_ENABLED304// send winch status message305void GCS_MAVLINK_Copter::send_winch_status() const306{307AP_Winch *winch = AP::winch();308if (winch == nullptr) {309return;310}311winch->send_status(*this);312}313#endif314315uint8_t GCS_MAVLINK_Copter::sysid_my_gcs() const316{317return copter.g.sysid_my_gcs;318}319bool GCS_MAVLINK_Copter::sysid_enforce() const320{321return copter.g2.sysid_enforce;322}323324uint32_t GCS_MAVLINK_Copter::telem_delay() const325{326return (uint32_t)(copter.g.telem_delay);327}328329bool GCS_Copter::vehicle_initialised() const {330return copter.ap.initialised;331}332333// try to send a message, return false if it wasn't sent334bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)335{336switch(id) {337338#if AP_TERRAIN_AVAILABLE339case MSG_TERRAIN_REQUEST:340CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);341copter.terrain.send_request(chan);342break;343case MSG_TERRAIN_REPORT:344CHECK_PAYLOAD_SIZE(TERRAIN_REPORT);345copter.terrain.send_report(chan);346break;347#endif348349case MSG_WIND:350CHECK_PAYLOAD_SIZE(WIND);351send_wind();352break;353354case MSG_SERVO_OUT:355case MSG_AOA_SSA:356case MSG_LANDING:357// unused358break;359360case MSG_ADSB_VEHICLE: {361#if HAL_ADSB_ENABLED362CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);363copter.adsb.send_adsb_vehicle(chan);364#endif365#if AP_OAPATHPLANNER_ENABLED366AP_OADatabase *oadb = AP_OADatabase::get_singleton();367if (oadb != nullptr) {368CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);369uint16_t interval_ms = 0;370if (get_ap_message_interval(id, interval_ms)) {371oadb->send_adsb_vehicle(chan, interval_ms);372}373}374#endif375break;376}377378default:379return GCS_MAVLINK::try_send_message(id);380}381return true;382}383384385const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {386// @Param: RAW_SENS387// @DisplayName: Raw sensor stream rate388// @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and AIRSPEED389// @Units: Hz390// @Range: 0 50391// @Increment: 1392// @RebootRequired: True393// @User: Advanced394AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 0),395396// @Param: EXT_STAT397// @DisplayName: Extended status stream rate398// @Description: MAVLink Stream rate of SYS_STATUS, POWER_STATUS, MCU_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW_INT (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, FENCE_STATUS, and GLOBAL_TARGET_POS_INT399// @Units: Hz400// @Range: 0 50401// @Increment: 1402// @RebootRequired: True403// @User: Advanced404AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 0),405406// @Param: RC_CHAN407// @DisplayName: RC Channel stream rate408// @Description: MAVLink Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS409// @Units: Hz410// @Range: 0 50411// @Increment: 1412// @RebootRequired: True413// @User: Advanced414AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 0),415416// @Param: RAW_CTRL417// @DisplayName: Unused418// @Description: Unused419// @Units: Hz420// @Range: 0 50421// @Increment: 1422// @RebootRequired: True423// @User: Advanced424AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 0),425426// @Param: POSITION427// @DisplayName: Position stream rate428// @Description: MAVLink Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED429// @Units: Hz430// @Range: 0 50431// @Increment: 1432// @RebootRequired: True433// @User: Advanced434AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 0),435436// @Param: EXTRA1437// @DisplayName: Extra data type 1 stream rate438// @Description: MAVLink Stream rate of ATTITUDE, SIMSTATE (SIM only), AHRS2 and PID_TUNING439// @Range: 0 50440// @Increment: 1441// @RebootRequired: True442// @User: Advanced443AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 0),444445// @Param: EXTRA2446// @DisplayName: Extra data type 2 stream rate447// @Description: MAVLink Stream rate of VFR_HUD448// @Units: Hz449// @Range: 0 50450// @Increment: 1451// @RebootRequired: True452// @User: Advanced453AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 0),454455// @Param: EXTRA3456// @DisplayName: Extra data type 3 stream rate457// @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, TERRAIN_REPORT, BATTERY_STATUS, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, RPM, ESC TELEMETRY,GENERATOR_STATUS, and WINCH_STATUS458459// @Units: Hz460// @Range: 0 50461// @Increment: 1462// @RebootRequired: True463// @User: Advanced464AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 0),465466// @Param: PARAMS467// @DisplayName: Parameter stream rate468// @Description: MAVLink Stream rate of PARAM_VALUE469// @Units: Hz470// @Range: 0 50471// @Increment: 1472// @RebootRequired: True473// @User: Advanced474AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 0),475476// @Param: ADSB477// @DisplayName: ADSB stream rate478// @Description: MAVLink ADSB stream rate479// @Units: Hz480// @Range: 0 50481// @Increment: 1482// @RebootRequired: True483// @User: Advanced484AP_GROUPINFO("ADSB", 9, GCS_MAVLINK_Parameters, streamRates[9], 0),485AP_GROUPEND486};487488static const ap_message STREAM_RAW_SENSORS_msgs[] = {489MSG_RAW_IMU,490MSG_SCALED_IMU2,491MSG_SCALED_IMU3,492MSG_SCALED_PRESSURE,493MSG_SCALED_PRESSURE2,494MSG_SCALED_PRESSURE3,495#if AP_AIRSPEED_ENABLED496MSG_AIRSPEED,497#endif498};499static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {500MSG_SYS_STATUS,501MSG_POWER_STATUS,502#if HAL_WITH_MCU_MONITORING503MSG_MCU_STATUS,504#endif505MSG_MEMINFO,506MSG_CURRENT_WAYPOINT, // MISSION_CURRENT507#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED508MSG_GPS_RAW,509#endif510#if AP_GPS_GPS_RTK_SENDING_ENABLED511MSG_GPS_RTK,512#endif513#if AP_GPS_GPS2_RAW_SENDING_ENABLED514MSG_GPS2_RAW,515#endif516#if AP_GPS_GPS2_RTK_SENDING_ENABLED517MSG_GPS2_RTK,518#endif519MSG_NAV_CONTROLLER_OUTPUT,520#if AP_FENCE_ENABLED521MSG_FENCE_STATUS,522#endif523MSG_POSITION_TARGET_GLOBAL_INT,524};525static const ap_message STREAM_POSITION_msgs[] = {526MSG_LOCATION,527MSG_LOCAL_POSITION528};529static const ap_message STREAM_RC_CHANNELS_msgs[] = {530MSG_SERVO_OUTPUT_RAW,531MSG_RC_CHANNELS,532#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED533MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection534#endif535};536static const ap_message STREAM_EXTRA1_msgs[] = {537MSG_ATTITUDE,538#if AP_SIM_ENABLED539MSG_SIMSTATE,540#endif541MSG_AHRS2,542MSG_PID_TUNING // Up to four PID_TUNING messages are sent, depending on GCS_PID_MASK parameter543};544static const ap_message STREAM_EXTRA2_msgs[] = {545MSG_VFR_HUD546};547static const ap_message STREAM_EXTRA3_msgs[] = {548MSG_AHRS,549MSG_SYSTEM_TIME,550MSG_WIND,551#if AP_RANGEFINDER_ENABLED552MSG_RANGEFINDER,553#endif554MSG_DISTANCE_SENSOR,555#if AP_TERRAIN_AVAILABLE556MSG_TERRAIN_REQUEST,557MSG_TERRAIN_REPORT,558#endif559#if AP_BATTERY_ENABLED560MSG_BATTERY_STATUS,561#endif562#if HAL_MOUNT_ENABLED563MSG_GIMBAL_DEVICE_ATTITUDE_STATUS,564#endif565#if AP_OPTICALFLOW_ENABLED566MSG_OPTICAL_FLOW,567#endif568#if COMPASS_CAL_ENABLED569MSG_MAG_CAL_REPORT,570MSG_MAG_CAL_PROGRESS,571#endif572MSG_EKF_STATUS_REPORT,573MSG_VIBRATION,574#if AP_RPM_ENABLED575MSG_RPM,576#endif577#if HAL_WITH_ESC_TELEM578MSG_ESC_TELEMETRY,579#endif580#if HAL_GENERATOR_ENABLED581MSG_GENERATOR_STATUS,582#endif583#if AP_WINCH_ENABLED584MSG_WINCH_STATUS,585#endif586#if HAL_EFI_ENABLED587MSG_EFI_STATUS,588#endif589};590static const ap_message STREAM_PARAMS_msgs[] = {591MSG_NEXT_PARAM,592MSG_AVAILABLE_MODES593};594static const ap_message STREAM_ADSB_msgs[] = {595MSG_ADSB_VEHICLE,596#if AP_AIS_ENABLED597MSG_AIS_VESSEL,598#endif599};600601const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {602MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),603MAV_STREAM_ENTRY(STREAM_EXTENDED_STATUS),604MAV_STREAM_ENTRY(STREAM_POSITION),605MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),606MAV_STREAM_ENTRY(STREAM_EXTRA1),607MAV_STREAM_ENTRY(STREAM_EXTRA2),608MAV_STREAM_ENTRY(STREAM_EXTRA3),609MAV_STREAM_ENTRY(STREAM_ADSB),610MAV_STREAM_ENTRY(STREAM_PARAMS),611MAV_STREAM_TERMINATOR // must have this at end of stream_entries612};613614MISSION_STATE GCS_MAVLINK_Copter::mission_state(const class AP_Mission &mission) const615{616if (copter.mode_auto.paused()) {617return MISSION_STATE_PAUSED;618}619return GCS_MAVLINK::mission_state(mission);620}621622bool GCS_MAVLINK_Copter::handle_guided_request(AP_Mission::Mission_Command &cmd)623{624#if MODE_AUTO_ENABLED625return copter.mode_auto.do_guided(cmd);626#else627return false;628#endif629}630631void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status,632const mavlink_message_t &msg)633{634// we handle these messages here to avoid them being blocked by mavlink routing code635#if HAL_ADSB_ENABLED636if (copter.g2.dev_options.get() & DevOptionADSBMAVLink) {637// optional handling of GLOBAL_POSITION_INT as a MAVLink based avoidance source638copter.avoidance_adsb.handle_msg(msg);639}640#endif641#if MODE_FOLLOW_ENABLED642// pass message to follow library643copter.g2.follow.handle_msg(msg);644#endif645GCS_MAVLINK::packetReceived(status, msg);646}647648bool GCS_MAVLINK_Copter::params_ready() const649{650if (AP_BoardConfig::in_config_error()) {651// we may never have parameters "initialised" in this case652return true;653}654// if we have not yet initialised (including allocating the motors655// object) we drop this request. That prevents the GCS from getting656// a confusing parameter count during bootup657return copter.ap.initialised_params;658}659660void GCS_MAVLINK_Copter::send_banner()661{662GCS_MAVLINK::send_banner();663if (copter.motors == nullptr) {664send_text(MAV_SEVERITY_INFO, "motors not allocated");665return;666}667char frame_and_type_string[30];668copter.motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));669send_text(MAV_SEVERITY_INFO, "%s", frame_and_type_string);670}671672void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t &msg)673{674copter.command_ack_counter++;675GCS_MAVLINK::handle_command_ack(msg);676}677678/*679handle a LANDING_TARGET command. The timestamp has been jitter corrected680*/681void GCS_MAVLINK_Copter::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)682{683#if AC_PRECLAND_ENABLED684copter.precland.handle_msg(packet, timestamp_ms);685#endif686}687688MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)689{690if (packet.y == 1) {691// compassmot calibration692return copter.mavlink_compassmot(*this);693}694695return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);696}697698699MAV_RESULT GCS_MAVLINK_Copter::handle_command_do_set_roi(const Location &roi_loc)700{701if (!roi_loc.check_latlng()) {702return MAV_RESULT_FAILED;703}704copter.flightmode->auto_yaw.set_roi(roi_loc);705return MAV_RESULT_ACCEPTED;706}707708MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg)709{710// reject reboot if user has also specified they want the "Auto" ESC calibration on next reboot711if (copter.g.esc_calibrate == (uint8_t)Copter::ESCCalibrationModes::ESCCAL_AUTO) {712send_text(MAV_SEVERITY_CRITICAL, "Reboot rejected, ESC cal on reboot");713return MAV_RESULT_FAILED;714}715716// call parent717return GCS_MAVLINK::handle_preflight_reboot(packet, msg);718}719720MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_command_int_t &packet)721{722#if MODE_GUIDED_ENABLED723const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;724if (!copter.flightmode->in_guided_mode() && !change_modes) {725return MAV_RESULT_DENIED;726}727728// sanity check location729if (!check_latlng(packet.x, packet.y)) {730return MAV_RESULT_DENIED;731}732733Location request_location;734if (!location_from_command_t(packet, request_location)) {735return MAV_RESULT_DENIED;736}737738if (request_location.sanitize(copter.current_loc)) {739// if the location wasn't already sane don't load it740return MAV_RESULT_DENIED; // failed as the location is not valid741}742743// we need to do this first, as we don't want to change the flight mode unless we can also set the target744if (!copter.mode_guided.set_destination(request_location, false, 0, false, 0)) {745return MAV_RESULT_FAILED;746}747748if (!copter.flightmode->in_guided_mode()) {749if (!copter.set_mode(Mode::Number::GUIDED, ModeReason::GCS_COMMAND)) {750return MAV_RESULT_FAILED;751}752// the position won't have been loaded if we had to change the flight mode, so load it again753if (!copter.mode_guided.set_destination(request_location, false, 0, false, 0)) {754return MAV_RESULT_FAILED;755}756}757758return MAV_RESULT_ACCEPTED;759#else760return MAV_RESULT_UNSUPPORTED;761#endif762}763764MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)765{766switch(packet.command) {767768case MAV_CMD_CONDITION_YAW:769return handle_MAV_CMD_CONDITION_YAW(packet);770771case MAV_CMD_DO_CHANGE_SPEED:772return handle_MAV_CMD_DO_CHANGE_SPEED(packet);773774#if MODE_FOLLOW_ENABLED775case MAV_CMD_DO_FOLLOW:776// param1: sysid of target to follow777if ((packet.param1 > 0) && (packet.param1 <= 255)) {778copter.g2.follow.set_target_sysid((uint8_t)packet.param1);779return MAV_RESULT_ACCEPTED;780}781return MAV_RESULT_DENIED;782#endif783784case MAV_CMD_DO_REPOSITION:785return handle_command_int_do_reposition(packet);786787// pause or resume an auto mission788case MAV_CMD_DO_PAUSE_CONTINUE:789return handle_command_pause_continue(packet);790791case MAV_CMD_DO_MOTOR_TEST:792return handle_MAV_CMD_DO_MOTOR_TEST(packet);793794case MAV_CMD_NAV_TAKEOFF:795case MAV_CMD_NAV_VTOL_TAKEOFF:796return handle_MAV_CMD_NAV_TAKEOFF(packet);797798#if HAL_PARACHUTE_ENABLED799case MAV_CMD_DO_PARACHUTE:800return handle_MAV_CMD_DO_PARACHUTE(packet);801#endif802803#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED804// Solo user presses pause button805case MAV_CMD_SOLO_BTN_PAUSE_CLICK:806return handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(packet);807// Solo user presses Fly button:808case MAV_CMD_SOLO_BTN_FLY_HOLD:809return handle_MAV_CMD_SOLO_BTN_FLY_HOLD(packet);810// Solo user holds down Fly button for a couple of seconds811case MAV_CMD_SOLO_BTN_FLY_CLICK:812return handle_MAV_CMD_SOLO_BTN_FLY_CLICK(packet);813#endif814815#if MODE_AUTO_ENABLED816case MAV_CMD_MISSION_START:817return handle_MAV_CMD_MISSION_START(packet);818#endif819820#if AP_WINCH_ENABLED821case MAV_CMD_DO_WINCH:822return handle_MAV_CMD_DO_WINCH(packet);823#endif824825case MAV_CMD_NAV_LOITER_UNLIM:826if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {827return MAV_RESULT_FAILED;828}829return MAV_RESULT_ACCEPTED;830831case MAV_CMD_NAV_RETURN_TO_LAUNCH:832if (!copter.set_mode(Mode::Number::RTL, ModeReason::GCS_COMMAND)) {833return MAV_RESULT_FAILED;834}835return MAV_RESULT_ACCEPTED;836837case MAV_CMD_NAV_VTOL_LAND:838case MAV_CMD_NAV_LAND:839if (!copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND)) {840return MAV_RESULT_FAILED;841}842return MAV_RESULT_ACCEPTED;843844#if MODE_AUTO_ENABLED845case MAV_CMD_DO_RETURN_PATH_START:846if (copter.mode_auto.return_path_start_auto_RTL(ModeReason::GCS_COMMAND)) {847return MAV_RESULT_ACCEPTED;848}849return MAV_RESULT_FAILED;850851case MAV_CMD_DO_LAND_START:852if (copter.mode_auto.jump_to_landing_sequence_auto_RTL(ModeReason::GCS_COMMAND)) {853return MAV_RESULT_ACCEPTED;854}855return MAV_RESULT_FAILED;856#endif857858default:859return GCS_MAVLINK::handle_command_int_packet(packet, msg);860}861}862863#if HAL_MOUNT_ENABLED864MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg)865{866switch (packet.command) {867case MAV_CMD_DO_MOUNT_CONTROL:868// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead869if (((MAV_MOUNT_MODE)packet.z == MAV_MOUNT_MODE_MAVLINK_TARGETING) &&870(copter.camera_mount.get_mount_type() != AP_Mount::Type::None) &&871!copter.camera_mount.has_pan_control()) {872// Per the handler in AP_Mount, DO_MOUNT_CONTROL yaw angle is in body frame, which is873// equivalent to an offset to the current yaw demand.874copter.flightmode->auto_yaw.set_yaw_angle_offset(packet.param3);875}876break;877default:878break;879}880return GCS_MAVLINK::handle_command_mount(packet, msg);881}882#endif883884MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet)885{886if (packet.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT) {887return MAV_RESULT_DENIED; // meaning some parameters are bad888}889890// param3 : horizontal navigation by pilot acceptable891// param4 : yaw angle (not supported)892// param5 : latitude (not supported)893// param6 : longitude (not supported)894// param7 : altitude [metres]895896float takeoff_alt = packet.z * 100; // Convert m to cm897898if (!copter.flightmode->do_user_takeoff(takeoff_alt, is_zero(packet.param3))) {899return MAV_RESULT_FAILED;900}901return MAV_RESULT_ACCEPTED;902}903904#if AP_MAVLINK_COMMAND_LONG_ENABLED905bool GCS_MAVLINK_Copter::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const906{907if (packet_command == MAV_CMD_NAV_TAKEOFF ||908packet_command == MAV_CMD_NAV_VTOL_TAKEOFF) {909frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;910return true;911}912return GCS_MAVLINK::mav_frame_for_command_long(frame, packet_command);913}914#endif915916917MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet)918{919// param1 : target angle [0-360]920// param2 : speed during change [deg per second]921// param3 : direction (-1:ccw, +1:cw)922// param4 : relative offset (1) or absolute angle (0)923if ((packet.param1 >= 0.0f) &&924(packet.param1 <= 360.0f) &&925(is_zero(packet.param4) || is_equal(packet.param4,1.0f))) {926copter.flightmode->auto_yaw.set_fixed_yaw(927packet.param1,928packet.param2,929(int8_t)packet.param3,930is_positive(packet.param4));931return MAV_RESULT_ACCEPTED;932}933return MAV_RESULT_FAILED;934}935936MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet)937{938// param1 : Speed type (0 or 1=Ground Speed, 2=Climb Speed, 3=Descent Speed)939// param2 : new speed in m/s940// param3 : unused941// param4 : unused942if (packet.param2 > 0.0f) {943if (packet.param1 > 2.9f) { // 3 = speed down944if (copter.flightmode->set_speed_down(packet.param2 * 100.0f)) {945return MAV_RESULT_ACCEPTED;946}947return MAV_RESULT_FAILED;948} else if (packet.param1 > 1.9f) { // 2 = speed up949if (copter.flightmode->set_speed_up(packet.param2 * 100.0f)) {950return MAV_RESULT_ACCEPTED;951}952return MAV_RESULT_FAILED;953} else {954if (copter.flightmode->set_speed_xy(packet.param2 * 100.0f)) {955return MAV_RESULT_ACCEPTED;956}957return MAV_RESULT_FAILED;958}959}960return MAV_RESULT_FAILED;961}962963#if MODE_AUTO_ENABLED964MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet)965{966if (!is_zero(packet.param1) || !is_zero(packet.param2)) {967// first-item/last item not supported968return MAV_RESULT_DENIED;969}970if (copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {971copter.set_auto_armed(true);972if (copter.mode_auto.mission.state() != AP_Mission::MISSION_RUNNING) {973copter.mode_auto.mission.start_or_resume();974}975return MAV_RESULT_ACCEPTED;976}977return MAV_RESULT_FAILED;978}979#endif980981982983#if HAL_PARACHUTE_ENABLED984MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)985{986// configure or release parachute987switch ((uint16_t)packet.param1) {988case PARACHUTE_DISABLE:989copter.parachute.enabled(false);990return MAV_RESULT_ACCEPTED;991case PARACHUTE_ENABLE:992copter.parachute.enabled(true);993return MAV_RESULT_ACCEPTED;994case PARACHUTE_RELEASE:995// treat as a manual release which performs some additional check of altitude996copter.parachute_manual_release();997return MAV_RESULT_ACCEPTED;998}999return MAV_RESULT_FAILED;1000}1001#endif10021003MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)1004{1005// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)1006// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)1007// param3 : throttle (range depends upon param2)1008// param4 : timeout (in seconds)1009// param5 : num_motors (in sequence)1010// param6 : motor test order1011return copter.mavlink_motor_test_start(*this,1012(uint8_t)packet.param1,1013(uint8_t)packet.param2,1014packet.param3,1015packet.param4,1016(uint8_t)packet.x);1017}10181019#if AP_WINCH_ENABLED1020MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_WINCH(const mavlink_command_int_t &packet)1021{1022// param1 : winch number (ignored)1023// param2 : action (0=relax, 1=relative length control, 2=rate control). See WINCH_ACTIONS enum.1024if (!copter.g2.winch.enabled()) {1025return MAV_RESULT_FAILED;1026}1027switch ((uint8_t)packet.param2) {1028case WINCH_RELAXED:1029copter.g2.winch.relax();1030return MAV_RESULT_ACCEPTED;1031case WINCH_RELATIVE_LENGTH_CONTROL: {1032copter.g2.winch.release_length(packet.param3);1033return MAV_RESULT_ACCEPTED;1034}1035case WINCH_RATE_CONTROL:1036copter.g2.winch.set_desired_rate(packet.param4);1037return MAV_RESULT_ACCEPTED;1038default:1039break;1040}1041return MAV_RESULT_FAILED;1042}1043#endif // AP_WINCH_ENABLED10441045#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED1046MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_FLY_CLICK(const mavlink_command_int_t &packet)1047{1048if (copter.failsafe.radio) {1049return MAV_RESULT_ACCEPTED;1050}10511052// set mode to Loiter or fall back to AltHold1053if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {1054copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_COMMAND);1055}1056return MAV_RESULT_ACCEPTED;1057}10581059MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_FLY_HOLD(const mavlink_command_int_t &packet)1060{1061if (copter.failsafe.radio) {1062return MAV_RESULT_ACCEPTED;1063}10641065if (!copter.motors->armed()) {1066// if disarmed, arm motors1067copter.arming.arm(AP_Arming::Method::MAVLINK);1068} else if (copter.ap.land_complete) {1069// if armed and landed, takeoff1070if (copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {1071copter.flightmode->do_user_takeoff(packet.param1*100, true);1072}1073} else {1074// if flying, land1075copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND);1076}1077return MAV_RESULT_ACCEPTED;1078}10791080MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(const mavlink_command_int_t &packet)1081{1082if (copter.failsafe.radio) {1083return MAV_RESULT_ACCEPTED;1084}10851086if (copter.motors->armed()) {1087if (copter.ap.land_complete) {1088// if landed, disarm motors1089copter.arming.disarm(AP_Arming::Method::SOLOPAUSEWHENLANDED);1090} else {1091// assume that shots modes are all done in guided.1092// NOTE: this may need to change if we add a non-guided shot mode1093bool shot_mode = (!is_zero(packet.param1) && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS));10941095if (!shot_mode) {1096#if MODE_BRAKE_ENABLED1097if (copter.set_mode(Mode::Number::BRAKE, ModeReason::GCS_COMMAND)) {1098copter.mode_brake.timeout_to_loiter_ms(2500);1099} else {1100copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_COMMAND);1101}1102#else1103copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_COMMAND);1104#endif1105} else {1106// SoloLink is expected to handle pause in shots1107}1108}1109}1110return MAV_RESULT_ACCEPTED;1111}1112#endif // AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED11131114MAV_RESULT GCS_MAVLINK_Copter::handle_command_pause_continue(const mavlink_command_int_t &packet)1115{1116// requested pause1117if ((uint8_t) packet.param1 == 0) {1118if (copter.flightmode->pause()) {1119return MAV_RESULT_ACCEPTED;1120}1121send_text(MAV_SEVERITY_INFO, "Failed to pause");1122return MAV_RESULT_FAILED;1123}11241125// requested resume1126if ((uint8_t) packet.param1 == 1) {1127if (copter.flightmode->resume()) {1128return MAV_RESULT_ACCEPTED;1129}1130send_text(MAV_SEVERITY_INFO, "Failed to resume");1131return MAV_RESULT_FAILED;1132}1133return MAV_RESULT_DENIED;1134}11351136#if HAL_MOUNT_ENABLED1137void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)1138{1139switch (msg.msgid) {1140case MAVLINK_MSG_ID_MOUNT_CONTROL:1141// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead1142if ((copter.camera_mount.get_mount_type() != AP_Mount::Type::None) &&1143(copter.camera_mount.get_mode() == MAV_MOUNT_MODE_MAVLINK_TARGETING) &&1144!copter.camera_mount.has_pan_control()) {1145// Per the handler in AP_Mount, MOUNT_CONTROL yaw angle is in body frame, which is1146// equivalent to an offset to the current yaw demand.1147const float yaw_offset_d = mavlink_msg_mount_control_get_input_c(&msg) * 0.01f;1148copter.flightmode->auto_yaw.set_yaw_angle_offset(yaw_offset_d);1149break;1150}1151}1152GCS_MAVLINK::handle_mount_message(msg);1153}1154#endif11551156// this is called on receipt of a MANUAL_CONTROL packet and is1157// expected to call manual_override to override RC input on desired1158// axes.1159void GCS_MAVLINK_Copter::handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow)1160{1161if (packet.z < 0) { // Copter doesn't do negative thrust1162return;1163}11641165manual_override(copter.channel_roll, packet.y, 1000, 2000, tnow);1166manual_override(copter.channel_pitch, packet.x, 1000, 2000, tnow, true);1167manual_override(copter.channel_throttle, packet.z, 0, 1000, tnow);1168manual_override(copter.channel_yaw, packet.r, 1000, 2000, tnow);1169}11701171// sanity check velocity or acceleration vector components are numbers1172// (e.g. not NaN) and below 1000. vec argument units are in meters/second or1173// metres/second/second1174bool GCS_MAVLINK_Copter::sane_vel_or_acc_vector(const Vector3f &vec) const1175{1176for (uint8_t i=0; i<3; i++) {1177// consider velocity invalid if any component nan or >1000(m/s or m/s/s)1178if (isnan(vec[i]) || fabsf(vec[i]) > 1000) {1179return false;1180}1181}1182return true;1183}11841185#if MODE_GUIDED_ENABLED1186// for mavlink SET_POSITION_TARGET messages1187constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE =1188POSITION_TARGET_TYPEMASK_X_IGNORE |1189POSITION_TARGET_TYPEMASK_Y_IGNORE |1190POSITION_TARGET_TYPEMASK_Z_IGNORE;11911192constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE =1193POSITION_TARGET_TYPEMASK_VX_IGNORE |1194POSITION_TARGET_TYPEMASK_VY_IGNORE |1195POSITION_TARGET_TYPEMASK_VZ_IGNORE;11961197constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE =1198POSITION_TARGET_TYPEMASK_AX_IGNORE |1199POSITION_TARGET_TYPEMASK_AY_IGNORE |1200POSITION_TARGET_TYPEMASK_AZ_IGNORE;12011202constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE =1203POSITION_TARGET_TYPEMASK_YAW_IGNORE;1204constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE =1205POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE;1206constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_FORCE_SET =1207POSITION_TARGET_TYPEMASK_FORCE_SET;1208#endif12091210#if MODE_GUIDED_ENABLED1211void GCS_MAVLINK_Copter::handle_message_set_attitude_target(const mavlink_message_t &msg)1212{1213// decode packet1214mavlink_set_attitude_target_t packet;1215mavlink_msg_set_attitude_target_decode(&msg, &packet);12161217// exit if vehicle is not in Guided mode or Auto-Guided mode1218if (!copter.flightmode->in_guided_mode()) {1219return;1220}12211222const bool roll_rate_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE;1223const bool pitch_rate_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE;1224const bool yaw_rate_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE;1225const bool throttle_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE;1226const bool attitude_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE;12271228// ensure thrust field is not ignored1229if (throttle_ignore) {1230// The throttle input is not defined1231return;1232}12331234Quaternion attitude_quat;1235if (attitude_ignore) {1236attitude_quat.zero();1237} else {1238attitude_quat = Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]);12391240// Do not accept the attitude_quaternion1241// if its magnitude is not close to unit length +/- 1E-31242// this limit is somewhat greater than sqrt(FLT_EPSL)1243if (!attitude_quat.is_unit_length()) {1244// The attitude quaternion is ill-defined1245return;1246}1247}12481249Vector3f ang_vel_body;1250if (!roll_rate_ignore && !pitch_rate_ignore && !yaw_rate_ignore) {1251ang_vel_body.x = packet.body_roll_rate;1252ang_vel_body.y = packet.body_pitch_rate;1253ang_vel_body.z = packet.body_yaw_rate;1254} else if (!(roll_rate_ignore && pitch_rate_ignore && yaw_rate_ignore)) {1255// The body rates are ill-defined1256// input is not valid so stop1257copter.mode_guided.init(true);1258return;1259}12601261// check if the message's thrust field should be interpreted as a climb rate or as thrust1262const bool use_thrust = copter.mode_guided.set_attitude_target_provides_thrust();12631264float climb_rate_or_thrust;1265if (use_thrust) {1266// interpret thrust as thrust1267climb_rate_or_thrust = constrain_float(packet.thrust, -1.0f, 1.0f);1268} else {1269// convert thrust to climb rate1270packet.thrust = constrain_float(packet.thrust, 0.0f, 1.0f);1271if (is_equal(packet.thrust, 0.5f)) {1272climb_rate_or_thrust = 0.0f;1273} else if (packet.thrust > 0.5f) {1274// climb at up to WPNAV_SPEED_UP1275climb_rate_or_thrust = (packet.thrust - 0.5f) * 2.0f * copter.wp_nav->get_default_speed_up();1276} else {1277// descend at up to WPNAV_SPEED_DN1278climb_rate_or_thrust = (0.5f - packet.thrust) * 2.0f * -copter.wp_nav->get_default_speed_down();1279}1280}12811282copter.mode_guided.set_angle(attitude_quat, ang_vel_body,1283climb_rate_or_thrust, use_thrust);1284}12851286void GCS_MAVLINK_Copter::handle_message_set_position_target_local_ned(const mavlink_message_t &msg)1287{1288// decode packet1289mavlink_set_position_target_local_ned_t packet;1290mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);12911292// exit if vehicle is not in Guided mode or Auto-Guided mode1293if (!copter.flightmode->in_guided_mode()) {1294return;1295}12961297// check for supported coordinate frames1298if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED &&1299packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&1300packet.coordinate_frame != MAV_FRAME_BODY_NED &&1301packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED) {1302// input is not valid so stop1303copter.mode_guided.init(true);1304return;1305}13061307bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;1308bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;1309bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;1310bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;1311bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;1312bool force_set = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE_SET;13131314// Force inputs are not supported1315// Do not accept command if force_set is true and acc_ignore is false1316if (force_set && !acc_ignore) {1317return;1318}13191320// prepare position1321Vector3f pos_vector;1322if (!pos_ignore) {1323// convert to cm1324pos_vector = Vector3f(packet.x * 100.0f, packet.y * 100.0f, -packet.z * 100.0f);1325// rotate to body-frame if necessary1326if (packet.coordinate_frame == MAV_FRAME_BODY_NED ||1327packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {1328copter.rotate_body_frame_to_NE(pos_vector.x, pos_vector.y);1329}1330// add body offset if necessary1331if (packet.coordinate_frame == MAV_FRAME_LOCAL_OFFSET_NED ||1332packet.coordinate_frame == MAV_FRAME_BODY_NED ||1333packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {1334pos_vector += copter.inertial_nav.get_position_neu_cm();1335}1336}13371338// prepare velocity1339Vector3f vel_vector;1340if (!vel_ignore) {1341vel_vector = Vector3f{packet.vx, packet.vy, -packet.vz};1342if (!sane_vel_or_acc_vector(vel_vector)) {1343// input is not valid so stop1344copter.mode_guided.init(true);1345return;1346}1347vel_vector *= 100; // m/s -> cm/s1348// rotate to body-frame if necessary1349if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {1350copter.rotate_body_frame_to_NE(vel_vector.x, vel_vector.y);1351}1352}13531354// prepare acceleration1355Vector3f accel_vector;1356if (!acc_ignore) {1357// convert to cm1358accel_vector = Vector3f(packet.afx * 100.0f, packet.afy * 100.0f, -packet.afz * 100.0f);1359// rotate to body-frame if necessary1360if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {1361copter.rotate_body_frame_to_NE(accel_vector.x, accel_vector.y);1362}1363}13641365// prepare yaw1366float yaw_cd = 0.0f;1367bool yaw_relative = false;1368float yaw_rate_cds = 0.0f;1369if (!yaw_ignore) {1370yaw_cd = ToDeg(packet.yaw) * 100.0f;1371yaw_relative = packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED;1372}1373if (!yaw_rate_ignore) {1374yaw_rate_cds = ToDeg(packet.yaw_rate) * 100.0f;1375}13761377// send request1378if (!pos_ignore && !vel_ignore) {1379copter.mode_guided.set_destination_posvelaccel(pos_vector, vel_vector, accel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);1380} else if (pos_ignore && !vel_ignore) {1381copter.mode_guided.set_velaccel(vel_vector, accel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);1382} else if (pos_ignore && vel_ignore && !acc_ignore) {1383copter.mode_guided.set_accel(accel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);1384} else if (!pos_ignore && vel_ignore && acc_ignore) {1385copter.mode_guided.set_destination(pos_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative, false);1386} else {1387// input is not valid so stop1388copter.mode_guided.init(true);1389}1390}13911392void GCS_MAVLINK_Copter::handle_message_set_position_target_global_int(const mavlink_message_t &msg)1393{1394// decode packet1395mavlink_set_position_target_global_int_t packet;1396mavlink_msg_set_position_target_global_int_decode(&msg, &packet);13971398// exit if vehicle is not in Guided mode or Auto-Guided mode1399if (!copter.flightmode->in_guided_mode()) {1400return;1401}14021403// todo: do we need to check for supported coordinate frames14041405bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;1406bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;1407bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;1408bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;1409bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;1410bool force_set = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE_SET;14111412// Force inputs are not supported1413// Do not accept command if force_set is true and acc_ignore is false1414if (force_set && !acc_ignore) {1415return;1416}14171418// extract location from message1419Location loc;1420if (!pos_ignore) {1421// sanity check location1422if (!check_latlng(packet.lat_int, packet.lon_int)) {1423// input is not valid so stop1424copter.mode_guided.init(true);1425return;1426}1427Location::AltFrame frame;1428if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.coordinate_frame, frame)) {1429// unknown coordinate frame1430// input is not valid so stop1431copter.mode_guided.init(true);1432return;1433}1434loc = {packet.lat_int, packet.lon_int, int32_t(packet.alt*100), frame};1435}14361437// prepare velocity1438Vector3f vel_vector;1439if (!vel_ignore) {1440vel_vector = Vector3f{packet.vx, packet.vy, -packet.vz};1441if (!sane_vel_or_acc_vector(vel_vector)) {1442// input is not valid so stop1443copter.mode_guided.init(true);1444return;1445}1446vel_vector *= 100; // m/s -> cm/s1447}14481449// prepare acceleration1450Vector3f accel_vector;1451if (!acc_ignore) {1452// convert to cm1453accel_vector = Vector3f(packet.afx * 100.0f, packet.afy * 100.0f, -packet.afz * 100.0f);1454}14551456// prepare yaw1457float yaw_cd = 0.0f;1458float yaw_rate_cds = 0.0f;1459if (!yaw_ignore) {1460yaw_cd = ToDeg(packet.yaw) * 100.0f;1461}1462if (!yaw_rate_ignore) {1463yaw_rate_cds = ToDeg(packet.yaw_rate) * 100.0f;1464}14651466// send targets to the appropriate guided mode controller1467if (!pos_ignore && !vel_ignore) {1468// convert Location to vector from ekf origin for posvel controller1469if (loc.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN) {1470// posvel controller does not support alt-above-terrain1471// input is not valid so stop1472copter.mode_guided.init(true);1473return;1474}1475Vector3f pos_neu_cm;1476if (!loc.get_vector_from_origin_NEU(pos_neu_cm)) {1477// input is not valid so stop1478copter.mode_guided.init(true);1479return;1480}1481copter.mode_guided.set_destination_posvel(pos_neu_cm, vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds);1482} else if (pos_ignore && !vel_ignore) {1483copter.mode_guided.set_velaccel(vel_vector, accel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds);1484} else if (pos_ignore && vel_ignore && !acc_ignore) {1485copter.mode_guided.set_accel(accel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds);1486} else if (!pos_ignore && vel_ignore && acc_ignore) {1487copter.mode_guided.set_destination(loc, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds);1488} else {1489// input is not valid so stop1490copter.mode_guided.init(true);1491}1492}1493#endif // MODE_GUIDED_ENABLED14941495void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)1496{14971498switch (msg.msgid) {1499#if MODE_GUIDED_ENABLED1500case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:1501handle_message_set_attitude_target(msg);1502break;1503case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:1504handle_message_set_position_target_local_ned(msg);1505break;1506case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:1507handle_message_set_position_target_global_int(msg);1508break;1509#endif1510#if AP_TERRAIN_AVAILABLE1511case MAVLINK_MSG_ID_TERRAIN_DATA:1512case MAVLINK_MSG_ID_TERRAIN_CHECK:1513copter.terrain.handle_data(chan, msg);1514break;1515#endif1516#if TOY_MODE_ENABLED1517case MAVLINK_MSG_ID_NAMED_VALUE_INT:1518copter.g2.toy_mode.handle_message(msg);1519break;1520#endif1521default:1522GCS_MAVLINK::handle_message(msg);1523break;1524}1525}15261527MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_int_t &packet) {1528#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED1529if (GCS_MAVLINK::handle_flight_termination(packet) == MAV_RESULT_ACCEPTED) {1530return MAV_RESULT_ACCEPTED;1531}1532#endif1533if (packet.param1 > 0.5f) {1534copter.arming.disarm(AP_Arming::Method::TERMINATION);1535return MAV_RESULT_ACCEPTED;1536}15371538return MAV_RESULT_FAILED;1539}15401541float GCS_MAVLINK_Copter::vfr_hud_alt() const1542{1543if (copter.g2.dev_options.get() & DevOptionVFR_HUDRelativeAlt) {1544// compatibility option for older mavlink-aware devices that1545// assume Copter returns a relative altitude in VFR_HUD.alt1546return copter.current_loc.alt * 0.01f;1547}1548return GCS_MAVLINK::vfr_hud_alt();1549}15501551uint64_t GCS_MAVLINK_Copter::capabilities() const1552{1553return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |1554MAV_PROTOCOL_CAPABILITY_MISSION_INT |1555MAV_PROTOCOL_CAPABILITY_COMMAND_INT |1556MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |1557MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |1558MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION |1559MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |1560#if AP_TERRAIN_AVAILABLE1561(copter.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |1562#endif1563GCS_MAVLINK::capabilities());1564}15651566MAV_LANDED_STATE GCS_MAVLINK_Copter::landed_state() const1567{1568if (copter.ap.land_complete) {1569return MAV_LANDED_STATE_ON_GROUND;1570}1571if (copter.flightmode->is_landing()) {1572return MAV_LANDED_STATE_LANDING;1573}1574if (copter.flightmode->is_taking_off()) {1575return MAV_LANDED_STATE_TAKEOFF;1576}1577return MAV_LANDED_STATE_IN_AIR;1578}15791580void GCS_MAVLINK_Copter::send_wind() const1581{1582Vector3f airspeed_vec_bf;1583if (!AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {1584// if we don't have an airspeed estimate then we don't have a1585// valid wind estimate on copters1586return;1587}1588const Vector3f wind = AP::ahrs().wind_estimate();1589mavlink_msg_wind_send(1590chan,1591degrees(atan2f(-wind.y, -wind.x)),1592wind.length(),1593wind.z);1594}15951596#if HAL_HIGH_LATENCY2_ENABLED1597int16_t GCS_MAVLINK_Copter::high_latency_target_altitude() const1598{1599AP_AHRS &ahrs = AP::ahrs();1600Location global_position_current;1601UNUSED_RESULT(ahrs.get_location(global_position_current));16021603//return units are m1604if (copter.ap.initialised) {1605return 0.01 * (global_position_current.alt + copter.pos_control->get_pos_error_z_cm());1606}1607return 0;16081609}16101611uint8_t GCS_MAVLINK_Copter::high_latency_tgt_heading() const1612{1613if (copter.ap.initialised) {1614// return units are deg/21615const Mode *flightmode = copter.flightmode;1616// need to convert -18000->18000 to 0->360/21617return wrap_360_cd(flightmode->wp_bearing()) / 200;1618}1619return 0;1620}16211622uint16_t GCS_MAVLINK_Copter::high_latency_tgt_dist() const1623{1624if (copter.ap.initialised) {1625// return units are dm1626const Mode *flightmode = copter.flightmode;1627return MIN(flightmode->wp_distance() * 1.0e-2, UINT16_MAX) / 10;1628}1629return 0;1630}16311632uint8_t GCS_MAVLINK_Copter::high_latency_tgt_airspeed() const1633{1634if (copter.ap.initialised) {1635// return units are m/s*51636return MIN(copter.pos_control->get_vel_target_cms().length() * 5.0e-2, UINT8_MAX);1637}1638return 0;1639}16401641uint8_t GCS_MAVLINK_Copter::high_latency_wind_speed() const1642{1643Vector3f airspeed_vec_bf;1644Vector3f wind;1645// return units are m/s*51646if (AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {1647wind = AP::ahrs().wind_estimate();1648return wind.length() * 5;1649}1650return 0;1651}16521653uint8_t GCS_MAVLINK_Copter::high_latency_wind_direction() const1654{1655Vector3f airspeed_vec_bf;1656Vector3f wind;1657// return units are deg/21658if (AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {1659wind = AP::ahrs().wind_estimate();1660// need to convert -180->180 to 0->360/21661return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;1662}1663return 0;1664}1665#endif // HAL_HIGH_LATENCY2_ENABLED16661667// Send the mode with the given index (not mode number!) return the total number of modes1668// Index starts at 11669uint8_t GCS_MAVLINK_Copter::send_available_mode(uint8_t index) const1670{1671const Mode* modes[] {1672#if MODE_AUTO_ENABLED1673&copter.mode_auto, // This auto is actually auto RTL!1674&copter.mode_auto, // This one is really is auto!1675#endif1676#if MODE_ACRO_ENABLED1677&copter.mode_acro,1678#endif1679&copter.mode_stabilize,1680&copter.mode_althold,1681#if MODE_CIRCLE_ENABLED1682&copter.mode_circle,1683#endif1684#if MODE_LOITER_ENABLED1685&copter.mode_loiter,1686#endif1687#if MODE_GUIDED_ENABLED1688&copter.mode_guided,1689#endif1690&copter.mode_land,1691#if MODE_RTL_ENABLED1692&copter.mode_rtl,1693#endif1694#if MODE_DRIFT_ENABLED1695&copter.mode_drift,1696#endif1697#if MODE_SPORT_ENABLED1698&copter.mode_sport,1699#endif1700#if MODE_FLIP_ENABLED1701&copter.mode_flip,1702#endif1703#if AUTOTUNE_ENABLED1704&copter.mode_autotune,1705#endif1706#if MODE_POSHOLD_ENABLED1707&copter.mode_poshold,1708#endif1709#if MODE_BRAKE_ENABLED1710&copter.mode_brake,1711#endif1712#if MODE_THROW_ENABLED1713&copter.mode_throw,1714#endif1715#if HAL_ADSB_ENABLED1716&copter.mode_avoid_adsb,1717#endif1718#if MODE_GUIDED_NOGPS_ENABLED1719&copter.mode_guided_nogps,1720#endif1721#if MODE_SMARTRTL_ENABLED1722&copter.mode_smartrtl,1723#endif1724#if MODE_FLOWHOLD_ENABLED1725(Mode*)copter.g2.mode_flowhold_ptr,1726#endif1727#if MODE_FOLLOW_ENABLED1728&copter.mode_follow,1729#endif1730#if MODE_ZIGZAG_ENABLED1731&copter.mode_zigzag,1732#endif1733#if MODE_SYSTEMID_ENABLED1734(Mode *)copter.g2.mode_systemid_ptr,1735#endif1736#if MODE_AUTOROTATE_ENABLED1737&copter.mode_autorotate,1738#endif1739#if MODE_TURTLE_ENABLED1740&copter.mode_turtle,1741#endif1742};17431744const uint8_t base_mode_count = ARRAY_SIZE(modes);1745uint8_t mode_count = base_mode_count;17461747#if AP_SCRIPTING_ENABLED1748for (uint8_t i = 0; i < ARRAY_SIZE(copter.mode_guided_custom); i++) {1749if (copter.mode_guided_custom[i] != nullptr) {1750mode_count += 1;1751}1752}1753#endif17541755// Convert to zero indexed1756const uint8_t index_zero = index - 1;1757if (index_zero >= mode_count) {1758// Mode does not exist!?1759return mode_count;1760}17611762// Ask the mode for its name and number1763const char* name;1764uint8_t mode_number;17651766if (index_zero < base_mode_count) {1767name = modes[index_zero]->name();1768mode_number = (uint8_t)modes[index_zero]->mode_number();17691770} else {1771#if AP_SCRIPTING_ENABLED1772const uint8_t custom_index = index_zero - base_mode_count;1773if (copter.mode_guided_custom[custom_index] == nullptr) {1774// Invalid index, should not happen1775return mode_count;1776}1777name = copter.mode_guided_custom[custom_index]->name();1778mode_number = (uint8_t)copter.mode_guided_custom[custom_index]->mode_number();1779#else1780// Should not endup here1781return mode_count;1782#endif1783}17841785#if MODE_AUTO_ENABLED1786// Auto RTL is odd1787// Have to deal with is separately becase its number and name can change depending on if were in it or not1788if (index_zero == 0) {1789mode_number = (uint8_t)Mode::Number::AUTO_RTL;1790name = "AUTO RTL";17911792} else if (index_zero == 1) {1793mode_number = (uint8_t)Mode::Number::AUTO;1794name = "AUTO";17951796}1797#endif17981799mavlink_msg_available_modes_send(1800chan,1801mode_count,1802index,1803MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,1804mode_number,18050, // MAV_MODE_PROPERTY bitmask1806name1807);18081809return mode_count;1810}181118121813