Path: blob/master/ArduCopter/GCS_MAVLink_Copter.cpp
9451 views
#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}2728uint8_t 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->NE_is_active()) {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 _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_ned_m;150Vector3f target_vel_ned_ms;151Vector3f target_accel_ned_mss;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_ned_m = copter.mode_guided.get_target_pos_NED_m().tofloat();165break;166case ModeGuided::SubMode::PosVelAccel:167type_mask = POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except position, velocity & acceleration168target_pos_ned_m = copter.mode_guided.get_target_pos_NED_m().tofloat();169target_vel_ned_ms = copter.mode_guided.get_target_vel_NED_ms();170target_accel_ned_mss = copter.mode_guided.get_target_accel_NED_mss();171break;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_ned_ms = copter.mode_guided.get_target_vel_NED_ms();176target_accel_ned_mss = copter.mode_guided.get_target_accel_NED_mss();177break;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_ned_mss = copter.mode_guided.get_target_accel_NED_mss();183break;184}185186mavlink_msg_position_target_local_ned_send(187chan,188AP_HAL::millis(), // time boot ms189MAV_FRAME_LOCAL_NED,190type_mask,191target_pos_ned_m.x, // x in metres192target_pos_ned_m.y, // y in metres193target_pos_ned_m.z, // z in metres NED frame194target_vel_ned_ms.x, // vx in m/s195target_vel_ned_ms.y, // vy in m/s196target_vel_ned_ms.z, // vz in m/s NED frame197target_accel_ned_mss.x, // afx in m/s/s198target_accel_ned_mss.y, // afy in m/s/s199target_accel_ned_mss.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_rad = copter.attitude_control->get_att_target_euler_rad();211const Mode *flightmode = copter.flightmode;212mavlink_msg_nav_controller_output_send(213chan,214degrees(targets_rad.x),215degrees(targets_rad.y),216degrees(targets_rad.z),217flightmode->wp_bearing_deg(),218MIN(flightmode->wp_distance_m(), UINT16_MAX),219copter.pos_control->get_pos_error_D_m(),2200,221flightmode->crosstrack_error_m());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_TAS(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->D_get_accel_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#endif314315bool GCS_Copter::vehicle_initialised() const {316return copter.ap.initialised;317}318319// try to send a message, return false if it wasn't sent320bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)321{322switch(id) {323324case MSG_WIND:325CHECK_PAYLOAD_SIZE(WIND);326send_wind();327break;328329case MSG_ADSB_VEHICLE: {330#if HAL_ADSB_ENABLED331CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);332copter.adsb.send_adsb_vehicle(chan);333#endif334#if AP_OAPATHPLANNER_ENABLED335AP_OADatabase *oadb = AP_OADatabase::get_singleton();336if (oadb != nullptr) {337CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);338uint16_t interval_ms = 0;339if (get_ap_message_interval(id, interval_ms)) {340oadb->send_adsb_vehicle(chan, interval_ms);341}342}343#endif344break;345}346347default:348return GCS_MAVLINK::try_send_message(id);349}350return true;351}352353354MISSION_STATE GCS_MAVLINK_Copter::mission_state(const class AP_Mission &mission) const355{356if (copter.mode_auto.paused()) {357return MISSION_STATE_PAUSED;358}359return GCS_MAVLINK::mission_state(mission);360}361362bool GCS_MAVLINK_Copter::handle_guided_request(AP_Mission::Mission_Command &cmd)363{364#if MODE_AUTO_ENABLED365return copter.mode_auto.do_guided(cmd);366#else367return false;368#endif369}370371void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status,372const mavlink_message_t &msg)373{374// we handle these messages here to avoid them being blocked by mavlink routing code375#if AP_ADSB_AVOIDANCE_ENABLED376if (copter.g2.dev_options.get() & DevOptionADSBMAVLink) {377// optional handling of GLOBAL_POSITION_INT as a MAVLink based avoidance source378copter.avoidance_adsb.handle_msg(msg);379}380#endif381GCS_MAVLINK::packetReceived(status, msg);382}383384bool GCS_MAVLINK_Copter::params_ready() const385{386if (AP_BoardConfig::in_config_error()) {387// we may never have parameters "initialised" in this case388return true;389}390// if we have not yet initialised (including allocating the motors391// object) we drop this request. That prevents the GCS from getting392// a confusing parameter count during bootup393return copter.ap.initialised_params;394}395396void GCS_MAVLINK_Copter::send_banner()397{398GCS_MAVLINK::send_banner();399if (copter.motors == nullptr) {400send_text(MAV_SEVERITY_INFO, "motors not allocated");401return;402}403char frame_and_type_string[30];404copter.motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));405send_text(MAV_SEVERITY_INFO, "%s", frame_and_type_string);406}407408void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t &msg)409{410copter.command_ack_counter++;411GCS_MAVLINK::handle_command_ack(msg);412}413414/*415handle a LANDING_TARGET command. The timestamp has been jitter corrected416*/417void GCS_MAVLINK_Copter::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)418{419#if AC_PRECLAND_ENABLED420copter.precland.handle_msg(packet, timestamp_ms);421#endif422}423424MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)425{426if (packet.y == 1) {427// compassmot calibration428return copter.mavlink_compassmot(*this);429}430431return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);432}433434435MAV_RESULT GCS_MAVLINK_Copter::handle_command_do_set_roi(const Location &roi_loc)436{437if (!roi_loc.check_latlng()) {438return MAV_RESULT_FAILED;439}440copter.flightmode->auto_yaw.set_roi(roi_loc);441return MAV_RESULT_ACCEPTED;442}443444MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg)445{446// reject reboot if user has also specified they want the "Auto" ESC calibration on next reboot447if (copter.g.esc_calibrate == (uint8_t)Copter::ESCCalibrationModes::ESCCAL_AUTO) {448send_text(MAV_SEVERITY_CRITICAL, "Reboot rejected, ESC cal on reboot");449return MAV_RESULT_FAILED;450}451452// call parent453return GCS_MAVLINK::handle_preflight_reboot(packet, msg);454}455456MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_command_int_t &packet)457{458#if MODE_GUIDED_ENABLED459const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;460if (!copter.flightmode->in_guided_mode() && !change_modes) {461return MAV_RESULT_DENIED;462}463464// sanity check location465if (!check_latlng(packet.x, packet.y)) {466return MAV_RESULT_DENIED;467}468469Location request_location;470if (!location_from_command_t(packet, request_location)) {471return MAV_RESULT_DENIED;472}473474if (request_location.sanitize(copter.current_loc)) {475// if the location wasn't already sane don't load it476return MAV_RESULT_DENIED; // failed as the location is not valid477}478479// we need to do this first, as we don't want to change the flight mode unless we can also set the target480if (!copter.mode_guided.set_destination(request_location, false, 0, false, 0)) {481return MAV_RESULT_FAILED;482}483484if (!copter.flightmode->in_guided_mode()) {485if (!copter.set_mode(Mode::Number::GUIDED, ModeReason::GCS_COMMAND)) {486return MAV_RESULT_FAILED;487}488// the position won't have been loaded if we had to change the flight mode, so load it again489if (!copter.mode_guided.set_destination(request_location, false, 0, false, 0)) {490return MAV_RESULT_FAILED;491}492}493494return MAV_RESULT_ACCEPTED;495#else496return MAV_RESULT_UNSUPPORTED;497#endif498}499500MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)501{502switch(packet.command) {503504case MAV_CMD_CONDITION_YAW:505return handle_MAV_CMD_CONDITION_YAW(packet);506507case MAV_CMD_DO_CHANGE_SPEED:508return handle_MAV_CMD_DO_CHANGE_SPEED(packet);509510case MAV_CMD_DO_REPOSITION:511return handle_command_int_do_reposition(packet);512513// pause or resume an auto mission514case MAV_CMD_DO_PAUSE_CONTINUE:515return handle_command_pause_continue(packet);516517case MAV_CMD_DO_MOTOR_TEST:518return handle_MAV_CMD_DO_MOTOR_TEST(packet);519520case MAV_CMD_NAV_TAKEOFF:521case MAV_CMD_NAV_VTOL_TAKEOFF:522return handle_MAV_CMD_NAV_TAKEOFF(packet);523524#if HAL_PARACHUTE_ENABLED525case MAV_CMD_DO_PARACHUTE:526return handle_MAV_CMD_DO_PARACHUTE(packet);527#endif528529#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED530// Solo user presses pause button531case MAV_CMD_SOLO_BTN_PAUSE_CLICK:532return handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(packet);533// Solo user presses Fly button:534case MAV_CMD_SOLO_BTN_FLY_HOLD:535return handle_MAV_CMD_SOLO_BTN_FLY_HOLD(packet);536// Solo user holds down Fly button for a couple of seconds537case MAV_CMD_SOLO_BTN_FLY_CLICK:538return handle_MAV_CMD_SOLO_BTN_FLY_CLICK(packet);539#endif540541#if MODE_AUTO_ENABLED542case MAV_CMD_MISSION_START:543return handle_MAV_CMD_MISSION_START(packet);544#endif545546#if AP_WINCH_ENABLED547case MAV_CMD_DO_WINCH:548return handle_MAV_CMD_DO_WINCH(packet);549#endif550551case MAV_CMD_NAV_LOITER_UNLIM:552if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {553return MAV_RESULT_FAILED;554}555return MAV_RESULT_ACCEPTED;556557case MAV_CMD_NAV_RETURN_TO_LAUNCH:558if (!copter.set_mode(Mode::Number::RTL, ModeReason::GCS_COMMAND)) {559return MAV_RESULT_FAILED;560}561return MAV_RESULT_ACCEPTED;562563case MAV_CMD_NAV_VTOL_LAND:564case MAV_CMD_NAV_LAND:565if (!copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND)) {566return MAV_RESULT_FAILED;567}568return MAV_RESULT_ACCEPTED;569570#if MODE_AUTO_ENABLED571case MAV_CMD_DO_RETURN_PATH_START:572if (copter.mode_auto.return_path_start_auto_RTL(ModeReason::GCS_COMMAND)) {573return MAV_RESULT_ACCEPTED;574}575return MAV_RESULT_FAILED;576577case MAV_CMD_DO_LAND_START:578if (copter.mode_auto.jump_to_landing_sequence_auto_RTL(ModeReason::GCS_COMMAND)) {579return MAV_RESULT_ACCEPTED;580}581return MAV_RESULT_FAILED;582#endif583584default:585return GCS_MAVLINK::handle_command_int_packet(packet, msg);586}587}588589#if HAL_MOUNT_ENABLED590MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg)591{592switch (packet.command) {593case MAV_CMD_DO_MOUNT_CONTROL:594// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead595if (((MAV_MOUNT_MODE)packet.z == MAV_MOUNT_MODE_MAVLINK_TARGETING) &&596(copter.camera_mount.get_mount_type() != AP_Mount::Type::None) &&597!copter.camera_mount.has_pan_control()) {598// Per the handler in AP_Mount, DO_MOUNT_CONTROL yaw angle is in body frame, which is599// equivalent to an offset to the current yaw demand.600copter.flightmode->auto_yaw.set_yaw_angle_offset_deg(packet.param3);601}602break;603default:604break;605}606return GCS_MAVLINK::handle_command_mount(packet, msg);607}608#endif609610MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet)611{612if (packet.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT) {613return MAV_RESULT_DENIED; // meaning some parameters are bad614}615616// param3 : horizontal navigation by pilot acceptable617// param4 : yaw angle (not supported)618// param5 : latitude (not supported)619// param6 : longitude (not supported)620// param7 : altitude [metres]621622float takeoff_alt_m = packet.z;623624if (!copter.flightmode->do_user_takeoff_U_m(takeoff_alt_m, is_zero(packet.param3))) {625return MAV_RESULT_FAILED;626}627return MAV_RESULT_ACCEPTED;628}629630#if AP_MAVLINK_COMMAND_LONG_ENABLED631bool GCS_MAVLINK_Copter::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const632{633if (packet_command == MAV_CMD_NAV_TAKEOFF ||634packet_command == MAV_CMD_NAV_VTOL_TAKEOFF) {635frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;636return true;637}638return GCS_MAVLINK::mav_frame_for_command_long(frame, packet_command);639}640#endif641642643MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet)644{645// param1 : target angle [0-360]646// param2 : speed during change [deg per second]647// param3 : direction (-1:ccw, +1:cw)648// param4 : relative offset (1) or absolute angle (0)649if ((packet.param1 >= 0.0f) &&650(packet.param1 <= 360.0f) &&651(is_zero(packet.param4) || is_equal(packet.param4,1.0f))) {652copter.flightmode->auto_yaw.set_fixed_yaw_rad(653radians(packet.param1),654radians(packet.param2),655(int8_t)packet.param3,656is_positive(packet.param4));657return MAV_RESULT_ACCEPTED;658}659return MAV_RESULT_FAILED;660}661662MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet)663{664if (!is_positive(packet.param2)) {665// Target speed must be larger than zero666return MAV_RESULT_DENIED;667}668669const float speed_ms = packet.param2;670671bool success = false;672switch (SPEED_TYPE(packet.param1)) {673case SPEED_TYPE_ENUM_END:674return MAV_RESULT_DENIED;675676case SPEED_TYPE_AIRSPEED: // Airspeed is treated as ground speed for GCS compatibility677case SPEED_TYPE_GROUNDSPEED:678success = copter.flightmode->set_speed_NE_ms(speed_ms);679break;680681case SPEED_TYPE_CLIMB_SPEED:682success = copter.flightmode->set_speed_up_ms(speed_ms);683break;684685case SPEED_TYPE_DESCENT_SPEED:686success = copter.flightmode->set_speed_down_ms(speed_ms);687break;688}689690return success ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;691}692693#if MODE_AUTO_ENABLED694MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet)695{696if (!is_zero(packet.param1) || !is_zero(packet.param2)) {697// first-item/last item not supported698return MAV_RESULT_DENIED;699}700if (copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {701copter.set_auto_armed(true);702if (copter.mode_auto.mission.state() != AP_Mission::MISSION_RUNNING) {703copter.mode_auto.mission.start_or_resume();704}705return MAV_RESULT_ACCEPTED;706}707return MAV_RESULT_FAILED;708}709#endif710711712713#if HAL_PARACHUTE_ENABLED714MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)715{716// configure or release parachute717switch ((uint16_t)packet.param1) {718case PARACHUTE_DISABLE:719copter.parachute.enabled(false);720return MAV_RESULT_ACCEPTED;721case PARACHUTE_ENABLE:722copter.parachute.enabled(true);723return MAV_RESULT_ACCEPTED;724case PARACHUTE_RELEASE:725// treat as a manual release which performs some additional check of altitude726copter.parachute_manual_release();727return MAV_RESULT_ACCEPTED;728}729return MAV_RESULT_FAILED;730}731#endif732733MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)734{735// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)736// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)737// param3 : throttle (range depends upon param2)738// param4 : timeout (in seconds)739// param5 : num_motors (in sequence)740// param6 : motor test order741return copter.mavlink_motor_test_start(*this,742(uint8_t)packet.param1,743(uint8_t)packet.param2,744packet.param3,745packet.param4,746(uint8_t)packet.x);747}748749#if AP_WINCH_ENABLED750MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_WINCH(const mavlink_command_int_t &packet)751{752// param1 : winch number (ignored)753// param2 : action (0=relax, 1=relative length control, 2=rate control). See WINCH_ACTIONS enum.754if (!copter.g2.winch.enabled()) {755return MAV_RESULT_FAILED;756}757switch ((uint8_t)packet.param2) {758case WINCH_RELAXED:759copter.g2.winch.relax();760return MAV_RESULT_ACCEPTED;761case WINCH_RELATIVE_LENGTH_CONTROL: {762copter.g2.winch.release_length(packet.param3);763return MAV_RESULT_ACCEPTED;764}765case WINCH_RATE_CONTROL:766copter.g2.winch.set_desired_rate(packet.param4);767return MAV_RESULT_ACCEPTED;768default:769break;770}771return MAV_RESULT_FAILED;772}773#endif // AP_WINCH_ENABLED774775#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED776MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_FLY_CLICK(const mavlink_command_int_t &packet)777{778if (copter.failsafe.radio) {779return MAV_RESULT_ACCEPTED;780}781782// set mode to Loiter or fall back to AltHold783if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {784copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_COMMAND);785}786return MAV_RESULT_ACCEPTED;787}788789MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_FLY_HOLD(const mavlink_command_int_t &packet)790{791if (copter.failsafe.radio) {792return MAV_RESULT_ACCEPTED;793}794795if (!copter.motors->armed()) {796// if disarmed, arm motors797copter.arming.arm(AP_Arming::Method::MAVLINK);798} else if (copter.ap.land_complete) {799// if armed and landed, takeoff800if (copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {801copter.flightmode->do_user_takeoff_U_m(packet.param1, true);802}803} else {804// if flying, land805copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND);806}807return MAV_RESULT_ACCEPTED;808}809810MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(const mavlink_command_int_t &packet)811{812if (copter.failsafe.radio) {813return MAV_RESULT_ACCEPTED;814}815816if (copter.motors->armed()) {817if (copter.ap.land_complete) {818// if landed, disarm motors819copter.arming.disarm(AP_Arming::Method::SOLOPAUSEWHENLANDED);820} else {821// assume that shots modes are all done in guided.822// NOTE: this may need to change if we add a non-guided shot mode823bool shot_mode = (!is_zero(packet.param1) && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS));824825if (!shot_mode) {826#if MODE_BRAKE_ENABLED827if (copter.set_mode(Mode::Number::BRAKE, ModeReason::GCS_COMMAND)) {828copter.mode_brake.timeout_to_loiter_ms(2500);829} else {830copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_COMMAND);831}832#else833copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_COMMAND);834#endif835} else {836// SoloLink is expected to handle pause in shots837}838}839}840return MAV_RESULT_ACCEPTED;841}842#endif // AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED843844MAV_RESULT GCS_MAVLINK_Copter::handle_command_pause_continue(const mavlink_command_int_t &packet)845{846// requested pause847if ((uint8_t) packet.param1 == 0) {848if (copter.flightmode->pause()) {849return MAV_RESULT_ACCEPTED;850}851send_text(MAV_SEVERITY_INFO, "Failed to pause");852return MAV_RESULT_FAILED;853}854855// requested resume856if ((uint8_t) packet.param1 == 1) {857if (copter.flightmode->resume()) {858return MAV_RESULT_ACCEPTED;859}860send_text(MAV_SEVERITY_INFO, "Failed to resume");861return MAV_RESULT_FAILED;862}863return MAV_RESULT_DENIED;864}865866// this is called on receipt of a MANUAL_CONTROL packet and is867// expected to call manual_override to override RC input on desired868// axes.869void GCS_MAVLINK_Copter::handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow)870{871if (packet.z < 0) { // Copter doesn't do negative thrust872return;873}874875manual_override(copter.channel_roll, packet.y, 1000, 2000, tnow);876manual_override(copter.channel_pitch, packet.x, 1000, 2000, tnow, true);877manual_override(copter.channel_throttle, packet.z, 0, 1000, tnow);878manual_override(copter.channel_yaw, packet.r, 1000, 2000, tnow);879}880881// sanity check velocity or acceleration vector components are numbers882// (e.g. not NaN) and below 1000. vec argument units are in meters/second or883// metres/second/second884bool GCS_MAVLINK_Copter::sane_vel_or_acc_vector(const Vector3f &vec) const885{886for (uint8_t i=0; i<3; i++) {887// consider velocity invalid if any component nan or >1000(m/s or m/s/s)888if (isnan(vec[i]) || fabsf(vec[i]) > 1000) {889return false;890}891}892return true;893}894895#if MODE_GUIDED_ENABLED896// for mavlink SET_POSITION_TARGET messages897constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE =898POSITION_TARGET_TYPEMASK_X_IGNORE |899POSITION_TARGET_TYPEMASK_Y_IGNORE |900POSITION_TARGET_TYPEMASK_Z_IGNORE;901902constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE =903POSITION_TARGET_TYPEMASK_VX_IGNORE |904POSITION_TARGET_TYPEMASK_VY_IGNORE |905POSITION_TARGET_TYPEMASK_VZ_IGNORE;906907constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE =908POSITION_TARGET_TYPEMASK_AX_IGNORE |909POSITION_TARGET_TYPEMASK_AY_IGNORE |910POSITION_TARGET_TYPEMASK_AZ_IGNORE;911912constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE =913POSITION_TARGET_TYPEMASK_YAW_IGNORE;914constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE =915POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE;916constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_FORCE_SET =917POSITION_TARGET_TYPEMASK_FORCE_SET;918#endif919920#if MODE_GUIDED_ENABLED921void GCS_MAVLINK_Copter::handle_message_set_attitude_target(const mavlink_message_t &msg)922{923// decode packet924mavlink_set_attitude_target_t packet;925mavlink_msg_set_attitude_target_decode(&msg, &packet);926927// exit if vehicle is not in Guided mode or Auto-Guided mode928if (!copter.flightmode->in_guided_mode()) {929return;930}931932const bool roll_rate_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE;933const bool pitch_rate_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE;934const bool yaw_rate_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE;935const bool throttle_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE;936const bool attitude_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE;937938// ensure thrust field is not ignored939if (throttle_ignore) {940// The throttle input is not defined941copter.mode_guided.hold_position();942return;943}944945Quaternion attitude_quat;946if (attitude_ignore) {947attitude_quat.zero();948} else {949attitude_quat = Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]);950951// Do not accept the attitude_quaternion952// if its magnitude is not close to unit length +/- 1E-3953// this limit is somewhat greater than sqrt(FLT_EPSL)954if (!attitude_quat.is_unit_length()) {955// The attitude quaternion is ill-defined956copter.mode_guided.hold_position();957return;958}959}960961Vector3f ang_vel_body;962if (!roll_rate_ignore && !pitch_rate_ignore && !yaw_rate_ignore) {963ang_vel_body.x = packet.body_roll_rate;964ang_vel_body.y = packet.body_pitch_rate;965ang_vel_body.z = packet.body_yaw_rate;966} else if (!(roll_rate_ignore && pitch_rate_ignore && yaw_rate_ignore)) {967// The body rates are ill-defined968copter.mode_guided.hold_position();969return;970}971972// check if the message's thrust field should be interpreted as a climb rate or as thrust973const bool use_thrust = copter.mode_guided.set_attitude_target_provides_thrust();974975float climb_rate_ms_or_thrust;976if (use_thrust) {977// interpret thrust as thrust978climb_rate_ms_or_thrust = constrain_float(packet.thrust, -1.0f, 1.0f);979} else {980// convert thrust to climb rate981packet.thrust = constrain_float(packet.thrust, 0.0f, 1.0f);982if (is_equal(packet.thrust, 0.5f)) {983climb_rate_ms_or_thrust = 0.0f;984} else if (packet.thrust > 0.5f) {985// climb at up to WPNAV_SPEED_UP986climb_rate_ms_or_thrust = (packet.thrust - 0.5f) * 2.0f * copter.wp_nav->get_default_speed_up_ms();987} else {988// descend at up to WPNAV_SPEED_DN989climb_rate_ms_or_thrust = (0.5f - packet.thrust) * 2.0f * -copter.wp_nav->get_default_speed_down_ms();990}991}992993copter.mode_guided.set_angle(attitude_quat, ang_vel_body,994climb_rate_ms_or_thrust, use_thrust);995}996997void GCS_MAVLINK_Copter::handle_message_set_position_target_local_ned(const mavlink_message_t &msg)998{999// decode packet1000mavlink_set_position_target_local_ned_t packet;1001mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);10021003// exit if vehicle is not in Guided mode or Auto-Guided mode1004if (!copter.flightmode->in_guided_mode()) {1005return;1006}10071008// check for supported coordinate frames1009if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED &&1010packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&1011packet.coordinate_frame != MAV_FRAME_BODY_NED &&1012packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED) {1013// unsupported coordinate frame1014copter.mode_guided.hold_position();1015return;1016}10171018bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;1019bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;1020bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;1021bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;1022bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;1023bool force_set = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE_SET;10241025// Force inputs are not supported1026// Do not accept command if force_set is true and acc_ignore is false1027if (force_set && !acc_ignore) {1028copter.mode_guided.hold_position();1029return;1030}10311032// prepare position1033Vector3p pos_ned_m;1034if (!pos_ignore) {1035// convert to m1036pos_ned_m = Vector3p{packet.x, packet.y, packet.z};1037// rotate to body-frame if necessary1038if (packet.coordinate_frame == MAV_FRAME_BODY_NED ||1039packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {1040pos_ned_m.xy() = copter.ahrs.body_to_earth2D_p(pos_ned_m.xy());1041}1042// add body offset if necessary1043if (packet.coordinate_frame == MAV_FRAME_LOCAL_OFFSET_NED ||1044packet.coordinate_frame == MAV_FRAME_BODY_NED ||1045packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {1046Vector3p rel_pos_ned_m;1047if (!AP::ahrs().get_relative_position_NED_origin(rel_pos_ned_m)) {1048// need position estimate to calculate target position1049copter.mode_guided.hold_position();1050return;1051}1052pos_ned_m += rel_pos_ned_m;1053}1054}10551056// prepare velocity1057Vector3f vel_ned_ms;1058if (!vel_ignore) {1059vel_ned_ms = Vector3f{packet.vx, packet.vy, packet.vz};1060if (!sane_vel_or_acc_vector(vel_ned_ms)) {1061// velocity vector contains NaN or Inf1062copter.mode_guided.hold_position();1063return;1064}1065// rotate to body-frame if necessary1066if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {1067vel_ned_ms.xy() = copter.ahrs.body_to_earth2D(vel_ned_ms.xy());1068}1069}10701071// prepare acceleration1072Vector3f accel_ned_mss;1073if (!acc_ignore) {1074accel_ned_mss = Vector3f{packet.afx, packet.afy, packet.afz};1075// rotate to body-frame if necessary1076if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {1077accel_ned_mss.xy() = copter.ahrs.body_to_earth2D(accel_ned_mss.xy());1078}1079}10801081// prepare yaw1082float yaw_rad = 0.0f;1083bool yaw_relative = false;1084float yaw_rate_rads = 0.0f;1085if (!yaw_ignore) {1086yaw_rad = packet.yaw;1087yaw_relative = packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED;1088}1089if (!yaw_rate_ignore) {1090yaw_rate_rads = packet.yaw_rate;1091}10921093// send request1094if (!pos_ignore && !vel_ignore) {1095copter.mode_guided.set_pos_vel_accel_NED_m(pos_ned_m, vel_ned_ms, accel_ned_mss, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads, yaw_relative);1096} else if (pos_ignore && !vel_ignore) {1097copter.mode_guided.set_vel_accel_NED_m(vel_ned_ms, accel_ned_mss, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads, yaw_relative);1098} else if (pos_ignore && vel_ignore && !acc_ignore) {1099copter.mode_guided.set_accel_NED_mss(accel_ned_mss, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads, yaw_relative);1100} else if (!pos_ignore && vel_ignore && acc_ignore) {1101copter.mode_guided.set_pos_NED_m(pos_ned_m, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads, yaw_relative, false);1102} else {1103// unsupported combination of position/velocity/acceleration flags1104copter.mode_guided.hold_position();1105}1106}11071108void GCS_MAVLINK_Copter::handle_message_set_position_target_global_int(const mavlink_message_t &msg)1109{1110// decode packet1111mavlink_set_position_target_global_int_t packet;1112mavlink_msg_set_position_target_global_int_decode(&msg, &packet);11131114// exit if vehicle is not in Guided mode or Auto-Guided mode1115if (!copter.flightmode->in_guided_mode()) {1116return;1117}11181119// todo: do we need to check for supported coordinate frames11201121bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;1122bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;1123bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;1124bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;1125bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;1126bool force_set = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE_SET;11271128// Force inputs are not supported1129// Do not accept command if force_set is true and acc_ignore is false1130if (force_set && !acc_ignore) {1131copter.mode_guided.hold_position();1132return;1133}11341135// extract location from message1136Location loc;1137if (!pos_ignore) {1138// sanity check location1139if (!check_latlng(packet.lat_int, packet.lon_int)) {1140// invalid latitude or longitude1141copter.mode_guided.hold_position();1142return;1143}1144Location::AltFrame frame;1145if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.coordinate_frame, frame)) {1146// unknown coordinate frame1147copter.mode_guided.hold_position();1148return;1149}1150loc = {packet.lat_int, packet.lon_int, int32_t(packet.alt*100), frame};1151}11521153// prepare velocity1154Vector3f vel_ned_ms;1155if (!vel_ignore) {1156vel_ned_ms = Vector3f{packet.vx, packet.vy, packet.vz};1157if (!sane_vel_or_acc_vector(vel_ned_ms)) {1158// velocity vector contains NaN or Inf1159copter.mode_guided.hold_position();1160return;1161}1162}11631164// prepare acceleration1165Vector3f accel_ned_mss;1166if (!acc_ignore) {1167accel_ned_mss = Vector3f{packet.afx, packet.afy, packet.afz};1168}11691170// prepare yaw1171float yaw_rad = 0.0f;1172float yaw_rate_rads = 0.0f;1173if (!yaw_ignore) {1174yaw_rad = packet.yaw;1175}1176if (!yaw_rate_ignore) {1177yaw_rate_rads = packet.yaw_rate;1178}11791180// send targets to the appropriate guided mode controller1181if (!pos_ignore && !vel_ignore) {1182// convert Location to vector from ekf origin for posvel controller1183if (loc.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN) {1184// posvel controller does not support alt-above-terrain1185copter.mode_guided.hold_position();1186return;1187}1188Vector3p pos_ned_m;1189if (!loc.get_vector_from_origin_NED_m(pos_ned_m)) {1190// could not convert location to NED position1191copter.mode_guided.hold_position();1192return;1193}1194copter.mode_guided.set_pos_vel_NED_m(pos_ned_m, vel_ned_ms, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads);1195} else if (pos_ignore && !vel_ignore) {1196copter.mode_guided.set_vel_accel_NED_m(vel_ned_ms, accel_ned_mss, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads);1197} else if (pos_ignore && vel_ignore && !acc_ignore) {1198copter.mode_guided.set_accel_NED_mss(accel_ned_mss, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads);1199} else if (!pos_ignore && vel_ignore && acc_ignore) {1200copter.mode_guided.set_destination(loc, !yaw_ignore, yaw_rad, !yaw_rate_ignore, yaw_rate_rads);1201} else {1202// unsupported combination of position/velocity/acceleration flags1203copter.mode_guided.hold_position();1204}1205}1206#endif // MODE_GUIDED_ENABLED12071208void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)1209{12101211switch (msg.msgid) {1212#if MODE_GUIDED_ENABLED1213case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:1214handle_message_set_attitude_target(msg);1215break;1216case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:1217handle_message_set_position_target_local_ned(msg);1218break;1219case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:1220handle_message_set_position_target_global_int(msg);1221break;1222#endif12231224#if TOY_MODE_ENABLED1225case MAVLINK_MSG_ID_NAMED_VALUE_INT:1226copter.g2.toy_mode.handle_message(msg);1227break;1228#endif1229default:1230GCS_MAVLINK::handle_message(msg);1231break;1232}1233}12341235MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_int_t &packet) {1236#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED1237if (GCS_MAVLINK::handle_flight_termination(packet) == MAV_RESULT_ACCEPTED) {1238return MAV_RESULT_ACCEPTED;1239}1240#endif1241if (packet.param1 > 0.5f) {1242copter.arming.disarm(AP_Arming::Method::TERMINATION);1243return MAV_RESULT_ACCEPTED;1244}12451246return MAV_RESULT_FAILED;1247}12481249float GCS_MAVLINK_Copter::vfr_hud_alt() const1250{1251if (copter.g2.dev_options.get() & DevOptionVFR_HUDRelativeAlt) {1252// compatibility option for older mavlink-aware devices that1253// assume Copter returns a relative altitude in VFR_HUD.alt1254return copter.current_loc.alt * 0.01f;1255}1256return GCS_MAVLINK::vfr_hud_alt();1257}12581259uint64_t GCS_MAVLINK_Copter::capabilities() const1260{1261return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |1262MAV_PROTOCOL_CAPABILITY_MISSION_INT |1263MAV_PROTOCOL_CAPABILITY_COMMAND_INT |1264MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |1265MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |1266MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION |1267MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |1268#if AP_TERRAIN_AVAILABLE1269(copter.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |1270#endif1271GCS_MAVLINK::capabilities());1272}12731274MAV_LANDED_STATE GCS_MAVLINK_Copter::landed_state() const1275{1276if (copter.ap.land_complete) {1277return MAV_LANDED_STATE_ON_GROUND;1278}1279if (copter.flightmode->is_landing()) {1280return MAV_LANDED_STATE_LANDING;1281}1282if (copter.flightmode->is_taking_off()) {1283return MAV_LANDED_STATE_TAKEOFF;1284}1285return MAV_LANDED_STATE_IN_AIR;1286}12871288void GCS_MAVLINK_Copter::send_wind() const1289{1290Vector3f airspeed_vec_bf;1291if (!AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {1292// if we don't have an airspeed estimate then we don't have a1293// valid wind estimate on copters1294return;1295}1296const Vector3f wind = AP::ahrs().wind_estimate();1297mavlink_msg_wind_send(1298chan,1299degrees(atan2f(-wind.y, -wind.x)),1300wind.length(),1301wind.z);1302}13031304#if HAL_HIGH_LATENCY2_ENABLED1305int16_t GCS_MAVLINK_Copter::high_latency_target_altitude() const1306{1307AP_AHRS &ahrs = AP::ahrs();1308Location global_position_current;1309UNUSED_RESULT(ahrs.get_location(global_position_current));13101311//return units are m1312if (copter.ap.initialised) {1313return global_position_current.alt * 0.01 - copter.pos_control->get_pos_error_D_m();1314}1315return 0;13161317}13181319uint8_t GCS_MAVLINK_Copter::high_latency_tgt_heading() const1320{1321if (copter.ap.initialised) {1322// return units are deg/21323const Mode *flightmode = copter.flightmode;1324// need to convert -180->180 to 0->360/21325return wrap_360(flightmode->wp_bearing_deg()) * 0.5;1326}1327return 0;1328}13291330uint16_t GCS_MAVLINK_Copter::high_latency_tgt_dist() const1331{1332if (copter.ap.initialised) {1333// return units are dm1334const Mode *flightmode = copter.flightmode;1335return MIN(flightmode->wp_distance_m(), UINT16_MAX) / 10;1336}1337return 0;1338}13391340uint8_t GCS_MAVLINK_Copter::high_latency_tgt_airspeed() const1341{1342if (copter.ap.initialised) {1343// return units are m/s*51344return MIN(copter.pos_control->get_vel_target_NED_ms().length() * 5.0, UINT8_MAX);1345}1346return 0;1347}13481349uint8_t GCS_MAVLINK_Copter::high_latency_wind_speed() const1350{1351Vector3f airspeed_vec_bf;1352Vector3f wind;1353// return units are m/s*51354if (AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {1355wind = AP::ahrs().wind_estimate();1356return wind.length() * 5;1357}1358return 0;1359}13601361uint8_t GCS_MAVLINK_Copter::high_latency_wind_direction() const1362{1363Vector3f airspeed_vec_bf;1364Vector3f wind;1365// return units are deg/21366if (AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {1367wind = AP::ahrs().wind_estimate();1368// need to convert -180->180 to 0->360/21369return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;1370}1371return 0;1372}1373#endif // HAL_HIGH_LATENCY2_ENABLED13741375// Send the mode with the given index (not mode number!) return the total number of modes1376// Index starts at 11377uint8_t GCS_MAVLINK_Copter::send_available_mode(uint8_t index) const1378{1379const Mode* modes[] {1380#if MODE_AUTO_ENABLED1381&copter.mode_auto, // This auto is actually auto RTL!1382&copter.mode_auto, // This one is really is auto!1383#endif1384#if MODE_ACRO_ENABLED1385&copter.mode_acro,1386#endif1387&copter.mode_stabilize,1388&copter.mode_althold,1389#if MODE_CIRCLE_ENABLED1390&copter.mode_circle,1391#endif1392#if MODE_LOITER_ENABLED1393&copter.mode_loiter,1394#endif1395#if MODE_GUIDED_ENABLED1396&copter.mode_guided,1397#endif1398&copter.mode_land,1399#if MODE_RTL_ENABLED1400&copter.mode_rtl,1401#endif1402#if MODE_DRIFT_ENABLED1403&copter.mode_drift,1404#endif1405#if MODE_SPORT_ENABLED1406&copter.mode_sport,1407#endif1408#if MODE_FLIP_ENABLED1409&copter.mode_flip,1410#endif1411#if AUTOTUNE_ENABLED1412&copter.mode_autotune,1413#endif1414#if MODE_POSHOLD_ENABLED1415&copter.mode_poshold,1416#endif1417#if MODE_BRAKE_ENABLED1418&copter.mode_brake,1419#endif1420#if MODE_THROW_ENABLED1421&copter.mode_throw,1422#endif1423#if AP_ADSB_AVOIDANCE_ENABLED1424&copter.mode_avoid_adsb,1425#endif1426#if MODE_GUIDED_NOGPS_ENABLED1427&copter.mode_guided_nogps,1428#endif1429#if MODE_SMARTRTL_ENABLED1430&copter.mode_smartrtl,1431#endif1432#if MODE_FLOWHOLD_ENABLED1433(Mode*)copter.g2.mode_flowhold_ptr,1434#endif1435#if MODE_FOLLOW_ENABLED1436&copter.mode_follow,1437#endif1438#if MODE_ZIGZAG_ENABLED1439&copter.mode_zigzag,1440#endif1441#if MODE_SYSTEMID_ENABLED1442(Mode *)copter.g2.mode_systemid_ptr,1443#endif1444#if MODE_AUTOROTATE_ENABLED1445&copter.mode_autorotate,1446#endif1447#if MODE_TURTLE_ENABLED1448&copter.mode_turtle,1449#endif1450};14511452const uint8_t base_mode_count = ARRAY_SIZE(modes);1453uint8_t mode_count = base_mode_count;14541455#if AP_SCRIPTING_ENABLED1456for (uint8_t i = 0; i < ARRAY_SIZE(copter.mode_guided_custom); i++) {1457if (copter.mode_guided_custom[i] != nullptr) {1458mode_count += 1;1459}1460}1461#endif14621463// Convert to zero indexed1464const uint8_t index_zero = index - 1;1465if (index_zero >= mode_count) {1466// Mode does not exist!?1467return mode_count;1468}14691470// Ask the mode for its name and number1471const char* name;1472uint8_t mode_number;14731474if (index_zero < base_mode_count) {1475name = modes[index_zero]->name();1476mode_number = (uint8_t)modes[index_zero]->mode_number();14771478} else {1479#if AP_SCRIPTING_ENABLED1480const uint8_t custom_index = index_zero - base_mode_count;1481if (copter.mode_guided_custom[custom_index] == nullptr) {1482// Invalid index, should not happen1483return mode_count;1484}1485name = copter.mode_guided_custom[custom_index]->name();1486mode_number = (uint8_t)copter.mode_guided_custom[custom_index]->mode_number();1487#else1488// Should not endup here1489return mode_count;1490#endif1491}14921493#if MODE_AUTO_ENABLED1494// Auto RTL is odd1495// Have to deal with is separately because its number and name can change depending on if were in it or not1496if (index_zero == 0) {1497mode_number = (uint8_t)Mode::Number::AUTO_RTL;1498name = "Auto RTL";14991500} else if (index_zero == 1) {1501mode_number = (uint8_t)Mode::Number::AUTO;1502name = "Auto";15031504}1505#endif15061507mavlink_msg_available_modes_send(1508chan,1509mode_count,1510index,1511MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,1512mode_number,15130, // MAV_MODE_PROPERTY bitmask1514name1515);15161517return mode_count;1518}151915201521