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/ArduPlane/GCS_MAVLink_Plane.cpp
Views: 1798
#include "GCS_MAVLink_Plane.h"12#include "Plane.h"3#include <AP_RPM/AP_RPM_config.h>4#include <AP_Airspeed/AP_Airspeed_config.h>5#include <AP_EFI/AP_EFI_config.h>67MAV_TYPE GCS_Plane::frame_type() const8{9#if HAL_QUADPLANE_ENABLED10return plane.quadplane.get_mav_type();11#else12return MAV_TYPE_FIXED_WING;13#endif14}1516MAV_MODE GCS_MAVLINK_Plane::base_mode() const17{18uint8_t _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;1920// work out the base_mode. This value is not very useful21// for APM, but we calculate it as best we can so a generic22// MAVLink enabled ground station can work out something about23// what the MAV is up to. The actual bit values are highly24// ambiguous for most of the APM flight modes. In practice, you25// only get useful information from the custom_mode, which maps to26// the APM flight mode and has a well defined meaning in the27// ArduPlane documentation28switch (plane.control_mode->mode_number()) {29case Mode::Number::MANUAL:30case Mode::Number::TRAINING:31case Mode::Number::ACRO:32#if HAL_QUADPLANE_ENABLED33case Mode::Number::QACRO:34_base_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;35break;36#endif37case Mode::Number::STABILIZE:38case Mode::Number::FLY_BY_WIRE_A:39case Mode::Number::AUTOTUNE:40case Mode::Number::FLY_BY_WIRE_B:41#if HAL_QUADPLANE_ENABLED42case Mode::Number::QSTABILIZE:43case Mode::Number::QHOVER:44case Mode::Number::QLOITER:45case Mode::Number::QLAND:46#if QAUTOTUNE_ENABLED47case Mode::Number::QAUTOTUNE:48#endif49#endif // HAL_QUADPLANE_ENABLED50case Mode::Number::CRUISE:51_base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;52break;53case Mode::Number::AUTO:54case Mode::Number::RTL:55case Mode::Number::LOITER:56case Mode::Number::THERMAL:57case Mode::Number::AVOID_ADSB:58case Mode::Number::GUIDED:59case Mode::Number::CIRCLE:60case Mode::Number::TAKEOFF:61#if MODE_AUTOLAND_ENABLED62case Mode::Number::AUTOLAND:63#endif64#if HAL_QUADPLANE_ENABLED65case Mode::Number::QRTL:66case Mode::Number::LOITER_ALT_QLAND:67#endif68_base_mode = MAV_MODE_FLAG_GUIDED_ENABLED |69MAV_MODE_FLAG_STABILIZE_ENABLED;70// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what71// APM does in any mode, as that is defined as "system finds its own goal72// positions", which APM does not currently do73break;74case Mode::Number::INITIALISING:75break;76}7778if (!plane.training_manual_pitch || !plane.training_manual_roll) {79_base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;80}8182if (plane.control_mode != &plane.mode_manual && plane.control_mode != &plane.mode_initializing) {83// stabiliser of some form is enabled84_base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;85}8687if (plane.g.stick_mixing != StickMixing::NONE && plane.control_mode != &plane.mode_initializing) {88if ((plane.g.stick_mixing != StickMixing::VTOL_YAW) || (plane.control_mode == &plane.mode_auto)) {89// all modes except INITIALISING have some form of manual90// override if stick mixing is enabled91_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;92}93}9495// we are armed if we are not initialising96if (plane.control_mode != &plane.mode_initializing && plane.arming.is_armed()) {97_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;98}99100// indicate we have set a custom mode101_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;102103return (MAV_MODE)_base_mode;104}105106uint32_t GCS_Plane::custom_mode() const107{108return plane.control_mode->mode_number();109}110111MAV_STATE GCS_MAVLINK_Plane::vehicle_system_status() const112{113if (plane.control_mode == &plane.mode_initializing) {114return MAV_STATE_CALIBRATING;115}116if (plane.any_failsafe_triggered()) {117return MAV_STATE_CRITICAL;118}119if (plane.crash_state.is_crashed) {120return MAV_STATE_EMERGENCY;121}122if (plane.is_flying()) {123return MAV_STATE_ACTIVE;124}125126return MAV_STATE_STANDBY;127}128129130void GCS_MAVLINK_Plane::send_attitude() const131{132const AP_AHRS &ahrs = AP::ahrs();133134float r = ahrs.get_roll();135float p = ahrs.get_pitch();136float y = ahrs.get_yaw();137138if (!(plane.flight_option_enabled(FlightOptions::GCS_REMOVE_TRIM_PITCH))) {139p -= radians(plane.g.pitch_trim);140}141142#if HAL_QUADPLANE_ENABLED143if (plane.quadplane.show_vtol_view()) {144r = plane.quadplane.ahrs_view->roll;145p = plane.quadplane.ahrs_view->pitch;146y = plane.quadplane.ahrs_view->yaw;147}148#endif149150const Vector3f &omega = ahrs.get_gyro();151mavlink_msg_attitude_send(152chan,153millis(),154r,155p,156y,157omega.x,158omega.y,159omega.z);160}161162void GCS_MAVLINK_Plane::send_attitude_target()163{164#if HAL_QUADPLANE_ENABLED165// Check if the attitude target is valid for reporting166const uint32_t now = AP_HAL::millis();167if (now - plane.quadplane.last_att_control_ms > 100) {168return;169}170171const Quaternion quat = plane.quadplane.attitude_control->get_attitude_target_quat();172const Vector3f& ang_vel = plane.quadplane.attitude_control->get_attitude_target_ang_vel();173const float throttle = plane.quadplane.attitude_control->get_throttle_in();174175const float quat_out[4] {quat.q1, quat.q2, quat.q3, quat.q4};176177const uint16_t typemask = 0;178179mavlink_msg_attitude_target_send(180chan,181now, // time since boot (ms)182typemask, // Bitmask that tells the system what control dimensions should be ignored by the vehicle183quat_out, // Target attitude quaternion [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], unit-length184ang_vel.x, // bodyframe target roll rate (rad/s)185ang_vel.y, // bodyframe target pitch rate (rad/s)186ang_vel.z, // bodyframe yaw rate (rad/s)187throttle); // Collective thrust, normalized to 0 .. 1188189#endif // HAL_QUADPLANE_ENABLED190}191192void GCS_MAVLINK_Plane::send_aoa_ssa()193{194AP_AHRS &ahrs = AP::ahrs();195196mavlink_msg_aoa_ssa_send(197chan,198micros(),199ahrs.getAOA(),200ahrs.getSSA());201}202203void GCS_MAVLINK_Plane::send_nav_controller_output() const204{205if (plane.control_mode == &plane.mode_manual) {206return;207}208#if HAL_QUADPLANE_ENABLED209const QuadPlane &quadplane = plane.quadplane;210if (quadplane.show_vtol_view() && quadplane.using_wp_nav()) {211const Vector3f &targets = quadplane.attitude_control->get_att_target_euler_cd();212213const Vector2f& curr_pos = quadplane.inertial_nav.get_position_xy_cm();214const Vector2f& target_pos = quadplane.pos_control->get_pos_target_cm().xy().tofloat();215const Vector2f error = (target_pos - curr_pos) * 0.01;216217mavlink_msg_nav_controller_output_send(218chan,219targets.x * 0.01,220targets.y * 0.01,221targets.z * 0.01,222degrees(error.angle()),223MIN(error.length(), UINT16_MAX),224(plane.control_mode != &plane.mode_qstabilize) ? quadplane.pos_control->get_pos_error_z_cm() * 0.01 : 0,225plane.airspeed_error * 100, // incorrect units; see PR#7933226quadplane.wp_nav->crosstrack_error());227return;228}229#endif230{231const AP_Navigation *nav_controller = plane.nav_controller;232mavlink_msg_nav_controller_output_send(233chan,234plane.nav_roll_cd * 0.01,235plane.nav_pitch_cd * 0.01,236nav_controller->nav_bearing_cd() * 0.01,237nav_controller->target_bearing_cd() * 0.01,238MIN(plane.auto_state.wp_distance, UINT16_MAX),239plane.calc_altitude_error_cm() * 0.01,240plane.airspeed_error * 100, // incorrect units; see PR#7933241nav_controller->crosstrack_error());242}243}244245void GCS_MAVLINK_Plane::send_position_target_global_int()246{247if (plane.control_mode == &plane.mode_manual) {248return;249}250Location &next_WP_loc = plane.next_WP_loc;251static constexpr uint16_t POSITION_TARGET_TYPEMASK_LAST_BYTE = 0xF000;252static constexpr uint16_t TYPE_MASK = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |253POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE |254POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE;255int32_t alt = 0;256if (!next_WP_loc.is_zero()) {257UNUSED_RESULT(next_WP_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt));258}259260mavlink_msg_position_target_global_int_send(261chan,262AP_HAL::millis(), // time_boot_ms263MAV_FRAME_GLOBAL, // targets are always global altitude264TYPE_MASK, // ignore everything except the x/y/z components265next_WP_loc.lat, // latitude as 1e7266next_WP_loc.lng, // longitude as 1e7267alt * 0.01, // altitude is sent as a float2680.0f, // vx2690.0f, // vy2700.0f, // vz2710.0f, // afx2720.0f, // afy2730.0f, // afz2740.0f, // yaw2750.0f); // yaw_rate276}277278279float GCS_MAVLINK_Plane::vfr_hud_airspeed() const280{281// airspeed sensors are best. While the AHRS airspeed_estimate282// will use an airspeed sensor, that value is constrained by the283// ground speed. When reporting we should send the true airspeed284// value if possible:285#if AP_AIRSPEED_ENABLED286if (plane.airspeed.enabled() && plane.airspeed.healthy()) {287return plane.airspeed.get_airspeed();288}289#endif290291// airspeed estimates are OK:292float aspeed;293if (AP::ahrs().airspeed_estimate(aspeed)) {294return aspeed;295}296297// lying is worst:298return 0;299}300301int16_t GCS_MAVLINK_Plane::vfr_hud_throttle() const302{303return plane.throttle_percentage();304}305306float GCS_MAVLINK_Plane::vfr_hud_climbrate() const307{308#if HAL_SOARING_ENABLED309if (plane.g2.soaring_controller.is_active()) {310return plane.g2.soaring_controller.get_vario_reading();311}312#endif313return GCS_MAVLINK::vfr_hud_climbrate();314}315316void GCS_MAVLINK_Plane::send_wind() const317{318const Vector3f wind = AP::ahrs().wind_estimate();319mavlink_msg_wind_send(320chan,321degrees(atan2f(-wind.y, -wind.x)), // use negative, to give322// direction wind is coming from323wind.length(),324wind.z);325}326327// sends a single pid info over the provided channel328void GCS_MAVLINK_Plane::send_pid_info(const AP_PIDInfo *pid_info,329const uint8_t axis, const float achieved)330{331if (pid_info == nullptr) {332return;333}334if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {335return;336}337mavlink_msg_pid_tuning_send(chan, axis,338pid_info->target,339achieved,340pid_info->FF,341pid_info->P,342pid_info->I,343pid_info->D,344pid_info->slew_rate,345pid_info->Dmod);346}347348/*349send PID tuning message350*/351void GCS_MAVLINK_Plane::send_pid_tuning()352{353if (plane.control_mode == &plane.mode_manual) {354// no PIDs should be used in manual355return;356}357358const Parameters &g = plane.g;359360const AP_PIDInfo *pid_info;361if (g.gcs_pid_mask & TUNING_BITS_ROLL) {362pid_info = &plane.rollController.get_pid_info();363#if HAL_QUADPLANE_ENABLED364if (plane.quadplane.in_vtol_mode()) {365pid_info = &plane.quadplane.attitude_control->get_rate_roll_pid().get_pid_info();366}367#endif368send_pid_info(pid_info, PID_TUNING_ROLL, pid_info->actual);369}370if (g.gcs_pid_mask & TUNING_BITS_PITCH) {371pid_info = &plane.pitchController.get_pid_info();372#if HAL_QUADPLANE_ENABLED373if (plane.quadplane.in_vtol_mode()) {374pid_info = &plane.quadplane.attitude_control->get_rate_pitch_pid().get_pid_info();375}376#endif377send_pid_info(pid_info, PID_TUNING_PITCH, pid_info->actual);378}379if (g.gcs_pid_mask & TUNING_BITS_YAW) {380pid_info = &plane.yawController.get_pid_info();381#if HAL_QUADPLANE_ENABLED382if (plane.quadplane.in_vtol_mode()) {383pid_info = &plane.quadplane.attitude_control->get_rate_yaw_pid().get_pid_info();384}385#endif386send_pid_info(pid_info, PID_TUNING_YAW, pid_info->actual);387}388if (g.gcs_pid_mask & TUNING_BITS_STEER) {389pid_info = &plane.steerController.get_pid_info();390send_pid_info(pid_info, PID_TUNING_STEER, pid_info->actual);391}392if ((g.gcs_pid_mask & TUNING_BITS_LAND) && (plane.flight_stage == AP_FixedWing::FlightStage::LAND)) {393AP_AHRS &ahrs = AP::ahrs();394const Vector3f &gyro = ahrs.get_gyro();395send_pid_info(plane.landing.get_pid_info(), PID_TUNING_LANDING, degrees(gyro.z));396}397#if HAL_QUADPLANE_ENABLED398if (g.gcs_pid_mask & TUNING_BITS_ACCZ && plane.quadplane.in_vtol_mode()) {399pid_info = &plane.quadplane.pos_control->get_accel_z_pid().get_pid_info();400send_pid_info(pid_info, PID_TUNING_ACCZ, pid_info->actual);401}402#endif403}404405uint8_t GCS_MAVLINK_Plane::sysid_my_gcs() const406{407return plane.g.sysid_my_gcs;408}409bool GCS_MAVLINK_Plane::sysid_enforce() const410{411return plane.g2.sysid_enforce;412}413414uint32_t GCS_MAVLINK_Plane::telem_delay() const415{416return (uint32_t)(plane.g.telem_delay);417}418419// try to send a message, return false if it won't fit in the serial tx buffer420bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)421{422switch (id) {423424case MSG_SERVO_OUT:425// unused426break;427428#if AP_TERRAIN_AVAILABLE429case MSG_TERRAIN_REQUEST:430CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);431plane.terrain.send_request(chan);432break;433case MSG_TERRAIN_REPORT:434CHECK_PAYLOAD_SIZE(TERRAIN_REPORT);435plane.terrain.send_report(chan);436break;437#endif438439case MSG_WIND:440CHECK_PAYLOAD_SIZE(WIND);441send_wind();442break;443444case MSG_ADSB_VEHICLE:445#if HAL_ADSB_ENABLED446CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);447plane.adsb.send_adsb_vehicle(chan);448#endif449break;450451case MSG_AOA_SSA:452CHECK_PAYLOAD_SIZE(AOA_SSA);453send_aoa_ssa();454break;455case MSG_LANDING:456plane.landing.send_landing_message(chan);457break;458459case MSG_HYGROMETER:460#if AP_AIRSPEED_HYGROMETER_ENABLE461CHECK_PAYLOAD_SIZE(HYGROMETER_SENSOR);462send_hygrometer();463#endif464break;465466default:467return GCS_MAVLINK::try_send_message(id);468}469return true;470}471472#if AP_AIRSPEED_HYGROMETER_ENABLE473void GCS_MAVLINK_Plane::send_hygrometer()474{475if (!HAVE_PAYLOAD_SPACE(chan, HYGROMETER_SENSOR)) {476return;477}478479const auto *airspeed = AP::airspeed();480if (airspeed == nullptr) {481return;482}483const uint32_t now = AP_HAL::millis();484485for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {486uint8_t idx = (i+last_hygrometer_send_idx+1) % AIRSPEED_MAX_SENSORS;487float temperature, humidity;488uint32_t last_sample_ms;489if (!airspeed->get_hygrometer(idx, last_sample_ms, temperature, humidity)) {490continue;491}492if (now - last_sample_ms > 2000) {493// not updating, stop sending494continue;495}496if (!HAVE_PAYLOAD_SPACE(chan, HYGROMETER_SENSOR)) {497return;498}499500mavlink_msg_hygrometer_sensor_send(501chan,502idx,503int16_t(temperature*100),504uint16_t(humidity*100));505last_hygrometer_send_idx = idx;506}507}508#endif // AP_AIRSPEED_HYGROMETER_ENABLE509510511/*512default stream rates to 1Hz513*/514const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {515// @Param: RAW_SENS516// @DisplayName: Raw sensor stream rate517// @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and AIRSPEED518// @Units: Hz519// @Range: 0 50520// @Increment: 1521// @RebootRequired: True522// @User: Advanced523AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1),524525// @Param: EXT_STAT526// @DisplayName: Extended status stream rate527// @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_INT528// @Units: Hz529// @Range: 0 50530// @Increment: 1531// @RebootRequired: True532// @User: Advanced533AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1),534535// @Param: RC_CHAN536// @DisplayName: RC Channel stream rate537// @Description: MAVLink Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS538// @Units: Hz539// @Range: 0 50540// @Increment: 1541// @RebootRequired: True542// @User: Advanced543AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1),544545// @Param: RAW_CTRL546// @DisplayName: Raw Control stream rate547// @Description: MAVLink Raw Control stream rate of SERVO_OUT548// @Units: Hz549// @Range: 0 50550// @Increment: 1551// @RebootRequired: True552// @User: Advanced553AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1),554555// @Param: POSITION556// @DisplayName: Position stream rate557// @Description: MAVLink Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED558// @Units: Hz559// @Range: 0 50560// @Increment: 1561// @RebootRequired: True562// @User: Advanced563AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 1),564565// @Param: EXTRA1566// @DisplayName: Extra data type 1 stream rate567// @Description: MAVLink Stream rate of ATTITUDE, SIMSTATE (SIM only), AHRS2, RPM, AOA_SSA, LANDING,ESC_TELEMETRY,EFI_STATUS, and PID_TUNING568// @Units: Hz569// @Range: 0 50570// @Increment: 1571// @RebootRequired: True572// @User: Advanced573AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1),574575// @Param: EXTRA2576// @DisplayName: Extra data type 2 stream rate577// @Description: MAVLink Stream rate of VFR_HUD578// @Range: 0 50579// @Increment: 1580// @RebootRequired: True581// @User: Advanced582AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1),583584// @Param: EXTRA3585// @DisplayName: Extra data type 3 stream rate586// @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, TERRAIN_REPORT, BATTERY2, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, and BATTERY_STATUS587// @Units: Hz588// @Range: 0 50589// @Increment: 1590// @RebootRequired: True591// @User: Advanced592AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1),593594// @Param: PARAMS595// @DisplayName: Parameter stream rate596// @Description: MAVLink Stream rate of PARAM_VALUE597// @Units: Hz598// @Range: 0 50599// @Increment: 1600// @RebootRequired: True601// @User: Advanced602AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10),603604// @Param: ADSB605// @DisplayName: ADSB stream rate606// @Description: MAVLink ADSB stream rate607// @Units: Hz608// @Range: 0 50609// @Increment: 1610// @RebootRequired: True611// @User: Advanced612AP_GROUPINFO("ADSB", 9, GCS_MAVLINK_Parameters, streamRates[9], 5),613AP_GROUPEND614};615616static const ap_message STREAM_RAW_SENSORS_msgs[] = {617MSG_RAW_IMU,618MSG_SCALED_IMU2,619MSG_SCALED_IMU3,620MSG_SCALED_PRESSURE,621MSG_SCALED_PRESSURE2,622MSG_SCALED_PRESSURE3,623#if AP_AIRSPEED_ENABLED624MSG_AIRSPEED,625#endif626};627static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {628MSG_SYS_STATUS,629MSG_POWER_STATUS,630#if HAL_WITH_MCU_MONITORING631MSG_MCU_STATUS,632#endif633MSG_MEMINFO,634MSG_CURRENT_WAYPOINT,635#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED636MSG_GPS_RAW,637#endif638#if AP_GPS_GPS_RTK_SENDING_ENABLED639MSG_GPS_RTK,640#endif641#if AP_GPS_GPS2_RAW_SENDING_ENABLED642MSG_GPS2_RAW,643#endif644#if AP_GPS_GPS2_RTK_SENDING_ENABLED645MSG_GPS2_RTK,646#endif647MSG_NAV_CONTROLLER_OUTPUT,648#if AP_FENCE_ENABLED649MSG_FENCE_STATUS,650#endif651MSG_POSITION_TARGET_GLOBAL_INT,652};653static const ap_message STREAM_POSITION_msgs[] = {654MSG_LOCATION,655MSG_LOCAL_POSITION656};657static const ap_message STREAM_RAW_CONTROLLER_msgs[] = {658MSG_SERVO_OUT,659};660static const ap_message STREAM_RC_CHANNELS_msgs[] = {661MSG_SERVO_OUTPUT_RAW,662MSG_RC_CHANNELS,663#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED664MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection665#endif666};667static const ap_message STREAM_EXTRA1_msgs[] = {668MSG_ATTITUDE,669#if AP_SIM_ENABLED670MSG_SIMSTATE,671#endif672MSG_AHRS2,673#if AP_RPM_ENABLED674MSG_RPM,675#endif676MSG_AOA_SSA,677MSG_PID_TUNING,678MSG_LANDING,679#if HAL_WITH_ESC_TELEM680MSG_ESC_TELEMETRY,681#endif682#if HAL_EFI_ENABLED683MSG_EFI_STATUS,684#endif685#if AP_AIRSPEED_HYGROMETER_ENABLE686MSG_HYGROMETER,687#endif688};689static const ap_message STREAM_EXTRA2_msgs[] = {690MSG_VFR_HUD691};692static const ap_message STREAM_EXTRA3_msgs[] = {693MSG_AHRS,694MSG_WIND,695#if AP_RANGEFINDER_ENABLED696MSG_RANGEFINDER,697#endif698MSG_DISTANCE_SENSOR,699MSG_SYSTEM_TIME,700#if AP_TERRAIN_AVAILABLE701MSG_TERRAIN_REPORT,702MSG_TERRAIN_REQUEST,703#endif704#if AP_BATTERY_ENABLED705MSG_BATTERY_STATUS,706#endif707#if HAL_MOUNT_ENABLED708MSG_GIMBAL_DEVICE_ATTITUDE_STATUS,709#endif710#if AP_OPTICALFLOW_ENABLED711MSG_OPTICAL_FLOW,712#endif713#if COMPASS_CAL_ENABLED714MSG_MAG_CAL_REPORT,715MSG_MAG_CAL_PROGRESS,716#endif717MSG_EKF_STATUS_REPORT,718MSG_VIBRATION,719};720static const ap_message STREAM_PARAMS_msgs[] = {721MSG_NEXT_PARAM,722MSG_AVAILABLE_MODES723};724static const ap_message STREAM_ADSB_msgs[] = {725MSG_ADSB_VEHICLE,726#if AP_AIS_ENABLED727MSG_AIS_VESSEL,728#endif729};730731const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {732MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),733MAV_STREAM_ENTRY(STREAM_EXTENDED_STATUS),734MAV_STREAM_ENTRY(STREAM_POSITION),735MAV_STREAM_ENTRY(STREAM_RAW_CONTROLLER),736MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),737MAV_STREAM_ENTRY(STREAM_EXTRA1),738MAV_STREAM_ENTRY(STREAM_EXTRA2),739MAV_STREAM_ENTRY(STREAM_EXTRA3),740MAV_STREAM_ENTRY(STREAM_PARAMS),741MAV_STREAM_ENTRY(STREAM_ADSB),742MAV_STREAM_TERMINATOR // must have this at end of stream_entries743};744745/*746handle a request to switch to guided mode. This happens via a747callback from handle_mission_item()748*/749bool GCS_MAVLINK_Plane::handle_guided_request(AP_Mission::Mission_Command &cmd)750{751return plane.control_mode->handle_guided_request(cmd.content.location);752}753754/*755handle a request to change current WP altitude. This happens via a756callback from handle_mission_item()757*/758void GCS_MAVLINK_Plane::handle_change_alt_request(AP_Mission::Mission_Command &cmd)759{760plane.next_WP_loc.alt = cmd.content.location.alt;761if (cmd.content.location.relative_alt) {762plane.next_WP_loc.alt += plane.home.alt;763}764plane.next_WP_loc.relative_alt = false;765plane.next_WP_loc.terrain_alt = cmd.content.location.terrain_alt;766plane.reset_offset_altitude();767}768769770/*771handle a LANDING_TARGET command. The timestamp has been jitter corrected772*/773void GCS_MAVLINK_Plane::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)774{775#if AC_PRECLAND_ENABLED776plane.g2.precland.handle_msg(packet, timestamp_ms);777#endif778}779780MAV_RESULT GCS_MAVLINK_Plane::handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)781{782plane.in_calibration = true;783MAV_RESULT ret = GCS_MAVLINK::handle_command_preflight_calibration(packet, msg);784plane.in_calibration = false;785786return ret;787}788789void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status,790const mavlink_message_t &msg)791{792#if HAL_ADSB_ENABLED793plane.avoidance_adsb.handle_msg(msg);794#endif795#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED796// pass message to follow library797plane.g2.follow.handle_msg(msg);798#endif799GCS_MAVLINK::packetReceived(status, msg);800}801802803bool Plane::set_home_to_current_location(bool _lock)804{805if (!set_home_persistently(AP::gps().location())) {806return false;807}808if (_lock) {809AP::ahrs().lock_home();810}811if ((control_mode == &mode_rtl)812#if HAL_QUADPLANE_ENABLED813|| (control_mode == &mode_qrtl)814#endif815) {816// if in RTL head to the updated home location817control_mode->enter();818}819return true;820}821bool Plane::set_home(const Location& loc, bool _lock)822{823if (!AP::ahrs().set_home(loc)) {824return false;825}826if (_lock) {827AP::ahrs().lock_home();828}829if ((control_mode == &mode_rtl)830#if HAL_QUADPLANE_ENABLED831|| (control_mode == &mode_qrtl)832#endif833) {834// if in RTL head to the updated home location835control_mode->enter();836}837return true;838}839840MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_do_reposition(const mavlink_command_int_t &packet)841{842// sanity check location843if (!check_latlng(packet.x, packet.y)) {844return MAV_RESULT_DENIED;845}846847Location requested_position;848if (!location_from_command_t(packet, requested_position)) {849return MAV_RESULT_DENIED;850}851852if (isnan(packet.param4) || is_zero(packet.param4)) {853requested_position.loiter_ccw = 0;854} else {855requested_position.loiter_ccw = 1;856}857858if (requested_position.sanitize(plane.current_loc)) {859// if the location wasn't already sane don't load it860return MAV_RESULT_DENIED;861}862863#if AP_FENCE_ENABLED864// reject destination if outside the fence865if (!plane.fence.check_destination_within_fence(requested_position)) {866LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);867return MAV_RESULT_DENIED;868}869#endif870871// location is valid load and set872if (((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) ||873(plane.control_mode == &plane.mode_guided)) {874plane.set_mode(plane.mode_guided, ModeReason::GCS_COMMAND);875#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED876plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;877#endif878879// add home alt if needed880if (requested_position.relative_alt) {881requested_position.alt += plane.home.alt;882requested_position.relative_alt = 0;883}884885plane.set_guided_WP(requested_position);886887// Loiter radius for planes. Positive radius in meters, direction is controlled by Yaw (param4) value, parsed above888if (!isnan(packet.param3) && packet.param3 > 0) {889plane.mode_guided.set_radius_and_direction(packet.param3, requested_position.loiter_ccw);890}891892return MAV_RESULT_ACCEPTED;893}894return MAV_RESULT_FAILED;895}896897#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED898// these are GUIDED mode commands that are RATE or slew enabled, so you can have more powerful control than default controls.899MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet)900{901switch(packet.command) {902case MAV_CMD_GUIDED_CHANGE_SPEED: {903// command is only valid in guided mode904if (plane.control_mode != &plane.mode_guided) {905return MAV_RESULT_FAILED;906}907908// only airspeed commands are supported right now...909if (int(packet.param1) != SPEED_TYPE_AIRSPEED) { // since SPEED_TYPE is int in range 0-1 and packet.param1 is a *float* this works.910return MAV_RESULT_DENIED;911}912913// reject airspeeds that are outside of the tuning envelope914if (packet.param2 > plane.aparm.airspeed_max || packet.param2 < plane.aparm.airspeed_min) {915return MAV_RESULT_DENIED;916}917918// no need to process any new packet/s with the919// same airspeed any further, if we are already doing it.920float new_target_airspeed_cm = packet.param2 * 100;921if ( is_equal(new_target_airspeed_cm,plane.guided_state.target_airspeed_cm)) {922return MAV_RESULT_ACCEPTED;923}924plane.guided_state.target_airspeed_cm = new_target_airspeed_cm;925plane.guided_state.target_airspeed_time_ms = AP_HAL::millis();926927if (is_zero(packet.param3)) {928// the user wanted /maximum acceleration, pick a large value as close enough929plane.guided_state.target_airspeed_accel = 1000.0f;930} else {931plane.guided_state.target_airspeed_accel = fabsf(packet.param3);932}933934// assign an acceleration direction935if (plane.guided_state.target_airspeed_cm < plane.target_airspeed_cm) {936plane.guided_state.target_airspeed_accel *= -1.0f;937}938return MAV_RESULT_ACCEPTED;939}940941case MAV_CMD_GUIDED_CHANGE_ALTITUDE: {942// command is only valid in guided943if (plane.control_mode != &plane.mode_guided) {944return MAV_RESULT_FAILED;945}946947// disallow default value of -1 and dangerous value of zero948if (is_equal(packet.z, -1.0f) || is_equal(packet.z, 0.0f)){949return MAV_RESULT_DENIED;950}951952Location::AltFrame new_target_alt_frame;953if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.frame, new_target_alt_frame)) {954return MAV_RESULT_DENIED;955}956// keep a copy of what came in via MAVLink - this is needed for logging, but not for anything else957plane.guided_state.target_mav_frame = packet.frame;958959const int32_t new_target_alt_cm = packet.z * 100;960plane.guided_state.target_location.set_alt_cm(new_target_alt_cm, new_target_alt_frame);961plane.guided_state.target_alt_time_ms = AP_HAL::millis();962963// param3 contains the desired vertical velocity (not acceleration)964if (is_zero(packet.param3)) {965// the user wanted /maximum altitude change rate, pick a large value as close enough966plane.guided_state.target_alt_rate = 1000.0;967} else {968plane.guided_state.target_alt_rate = fabsf(packet.param3);969}970971return MAV_RESULT_ACCEPTED;972}973974case MAV_CMD_GUIDED_CHANGE_HEADING: {975976// command is only valid in guided mode977if (plane.control_mode != &plane.mode_guided) {978return MAV_RESULT_FAILED;979}980981// don't accept packets outside of [0-360] degree range982if (packet.param2 < 0.0f || packet.param2 >= 360.0f) {983return MAV_RESULT_DENIED;984}985986float new_target_heading = radians(wrap_180(packet.param2));987988switch(HEADING_TYPE(packet.param1)) {989case HEADING_TYPE_COURSE_OVER_GROUND:990// course over ground991plane.guided_state.target_heading_type = GUIDED_HEADING_COG;992plane.prev_WP_loc = plane.current_loc;993break;994case HEADING_TYPE_HEADING:995// normal vehicle heading996plane.guided_state.target_heading_type = GUIDED_HEADING_HEADING;997break;998case HEADING_TYPE_DEFAULT:999plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;1000return MAV_RESULT_ACCEPTED;1001default:1002// MAV_RESULT_DENIED means Command is invalid (is supported but has invalid parameters).1003return MAV_RESULT_DENIED;1004}10051006plane.g2.guidedHeading.reset_I();10071008plane.guided_state.target_heading = new_target_heading;1009plane.guided_state.target_heading_accel_limit = MAX(packet.param3, 0.05f);1010plane.guided_state.target_heading_time_ms = AP_HAL::millis();1011return MAV_RESULT_ACCEPTED;1012}1013}1014// anything else ...1015return MAV_RESULT_UNSUPPORTED;1016}1017#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED10181019MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)1020{1021switch(packet.command) {10221023case MAV_CMD_DO_AUTOTUNE_ENABLE:1024return handle_MAV_CMD_DO_AUTOTUNE_ENABLE(packet);10251026case MAV_CMD_DO_REPOSITION:1027return handle_command_int_do_reposition(packet);10281029#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED1030// special 'slew-enabled' guided commands here... for speed,alt, and direction commands1031case MAV_CMD_GUIDED_CHANGE_SPEED:1032case MAV_CMD_GUIDED_CHANGE_ALTITUDE:1033case MAV_CMD_GUIDED_CHANGE_HEADING:1034return handle_command_int_guided_slew_commands(packet);1035#endif10361037#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED1038case MAV_CMD_DO_FOLLOW:1039// param1: sysid of target to follow1040if ((packet.param1 > 0) && (packet.param1 <= 255)) {1041plane.g2.follow.set_target_sysid((uint8_t)packet.param1);1042return MAV_RESULT_ACCEPTED;1043}1044return MAV_RESULT_DENIED;1045#endif10461047#if AP_ICENGINE_ENABLED1048case MAV_CMD_DO_ENGINE_CONTROL:1049if (!plane.g2.ice_control.engine_control(packet.param1, packet.param2, packet.param3, (uint32_t)packet.param4)) {1050return MAV_RESULT_FAILED;1051}1052return MAV_RESULT_ACCEPTED;1053#endif10541055case MAV_CMD_DO_CHANGE_SPEED:1056return handle_command_DO_CHANGE_SPEED(packet);10571058#if HAL_PARACHUTE_ENABLED1059case MAV_CMD_DO_PARACHUTE:1060return handle_MAV_CMD_DO_PARACHUTE(packet);1061#endif10621063#if HAL_QUADPLANE_ENABLED1064case MAV_CMD_DO_MOTOR_TEST:1065return handle_MAV_CMD_DO_MOTOR_TEST(packet);10661067case MAV_CMD_DO_VTOL_TRANSITION:1068return handle_command_DO_VTOL_TRANSITION(packet);10691070case MAV_CMD_NAV_TAKEOFF:1071return handle_command_MAV_CMD_NAV_TAKEOFF(packet);1072#endif10731074case MAV_CMD_DO_GO_AROUND:1075return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;10761077case MAV_CMD_DO_RETURN_PATH_START:1078// attempt to rejoin after the next DO_RETURN_PATH_START command in the mission1079if (plane.have_position && plane.mission.jump_to_closest_mission_leg(plane.current_loc)) {1080plane.mission.set_force_resume(true);1081if (plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND)) {1082return MAV_RESULT_ACCEPTED;1083}1084// mode change failed, revert force resume flag1085plane.mission.set_force_resume(false);1086}1087return MAV_RESULT_FAILED;10881089case MAV_CMD_DO_LAND_START:1090// attempt to switch to next DO_LAND_START command in the mission1091if (plane.have_position && plane.mission.jump_to_landing_sequence(plane.current_loc)) {1092plane.mission.set_force_resume(true);1093if (plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND)) {1094return MAV_RESULT_ACCEPTED;1095}1096// mode change failed, revert force resume flag1097plane.mission.set_force_resume(false);1098}1099return MAV_RESULT_FAILED;11001101case MAV_CMD_MISSION_START:1102if (!is_zero(packet.param1) || !is_zero(packet.param2)) {1103// first-item/last item not supported1104return MAV_RESULT_DENIED;1105}1106plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND);1107return MAV_RESULT_ACCEPTED;11081109case MAV_CMD_NAV_LOITER_UNLIM:1110plane.set_mode(plane.mode_loiter, ModeReason::GCS_COMMAND);1111return MAV_RESULT_ACCEPTED;11121113case MAV_CMD_NAV_RETURN_TO_LAUNCH:1114plane.set_mode(plane.mode_rtl, ModeReason::GCS_COMMAND);1115return MAV_RESULT_ACCEPTED;11161117#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED1118case MAV_CMD_SET_HAGL:1119plane.handle_external_hagl(packet);1120return MAV_RESULT_ACCEPTED;1121#endif11221123default:1124return GCS_MAVLINK::handle_command_int_packet(packet, msg);1125}1126}11271128MAV_RESULT GCS_MAVLINK_Plane::handle_command_DO_CHANGE_SPEED(const mavlink_command_int_t &packet)1129{1130// if we're in failsafe modes (e.g., RTL, LOITER) or in pilot1131// controlled modes (e.g., MANUAL, TRAINING)1132// this command should be ignored since it comes in from GCS1133// or a companion computer:1134if ((!plane.control_mode->is_guided_mode()) &&1135(plane.control_mode != &plane.mode_auto)) {1136// failed1137return MAV_RESULT_FAILED;1138}11391140if (plane.do_change_speed(packet.param1, packet.param2, packet.param3)) {1141return MAV_RESULT_ACCEPTED;1142}1143return MAV_RESULT_FAILED;1144}11451146#if HAL_QUADPLANE_ENABLED1147#if AP_MAVLINK_COMMAND_LONG_ENABLED1148void GCS_MAVLINK_Plane::convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out)1149{1150// convert to MAV_FRAME_LOCAL_OFFSET_NED, "NED local tangent frame1151// with origin that travels with the vehicle"1152out = {};1153out.target_system = in.target_system;1154out.target_component = in.target_component;1155out.frame = MAV_FRAME_LOCAL_OFFSET_NED;1156out.command = in.command;1157// out.current = 0;1158// out.autocontinue = 0;1159// out.param1 = in.param1; // we only use the "z" parameter in this command:1160// out.param2 = in.param2;1161// out.param3 = in.param3;1162// out.param4 = in.param4;1163// out.x = 0; // we don't handle positioning when doing takeoffs1164// out.y = 0;1165out.z = -in.param7; // up -> down1166}11671168void GCS_MAVLINK_Plane::convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame)1169{1170switch (in.command) {1171case MAV_CMD_NAV_TAKEOFF:1172convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(in, out);1173return;1174}1175return GCS_MAVLINK::convert_COMMAND_LONG_to_COMMAND_INT(in, out, frame);1176}1177#endif // AP_MAVLINK_COMMAND_LONG_ENABLED11781179MAV_RESULT GCS_MAVLINK_Plane::handle_command_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet)1180{1181float takeoff_alt = packet.z;1182switch (packet.frame) {1183case MAV_FRAME_LOCAL_OFFSET_NED: // "NED local tangent frame with origin that travels with the vehicle"1184takeoff_alt = -takeoff_alt; // down -> up1185break;1186default:1187return MAV_RESULT_DENIED; // "is supported but has invalid parameters"1188}1189if (!plane.quadplane.available()) {1190return MAV_RESULT_FAILED;1191}1192if (!plane.quadplane.do_user_takeoff(takeoff_alt)) {1193return MAV_RESULT_FAILED;1194}1195return MAV_RESULT_ACCEPTED;1196}1197#endif11981199MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_command_int_t &packet)1200{1201// param1 : enable/disable1202plane.autotune_enable(!is_zero(packet.param1));1203return MAV_RESULT_ACCEPTED;1204}12051206#if HAL_PARACHUTE_ENABLED1207MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)1208{1209// configure or release parachute1210switch ((uint16_t)packet.param1) {1211case PARACHUTE_DISABLE:1212plane.parachute.enabled(false);1213return MAV_RESULT_ACCEPTED;1214case PARACHUTE_ENABLE:1215plane.parachute.enabled(true);1216return MAV_RESULT_ACCEPTED;1217case PARACHUTE_RELEASE:1218// treat as a manual release which performs some additional check of altitude1219if (plane.parachute.released()) {1220gcs().send_text(MAV_SEVERITY_NOTICE, "Parachute already released");1221return MAV_RESULT_FAILED;1222}1223if (!plane.parachute.enabled()) {1224gcs().send_text(MAV_SEVERITY_NOTICE, "Parachute not enabled");1225return MAV_RESULT_FAILED;1226}1227if (!plane.parachute_manual_release()) {1228return MAV_RESULT_FAILED;1229}1230return MAV_RESULT_ACCEPTED;1231default:1232break;1233}1234return MAV_RESULT_FAILED;1235}1236#endif123712381239#if HAL_QUADPLANE_ENABLED1240MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)1241{1242// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)1243// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)1244// param3 : throttle (range depends upon param2)1245// param4 : timeout (in seconds)1246// param5 : motor count (number of motors to test in sequence)1247return plane.quadplane.mavlink_motor_test_start(chan,1248(uint8_t)packet.param1,1249(uint8_t)packet.param2,1250(uint16_t)packet.param3,1251packet.param4,1252(uint8_t)packet.x);1253}12541255MAV_RESULT GCS_MAVLINK_Plane::handle_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet)1256{1257if (!plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)packet.param1)) {1258return MAV_RESULT_FAILED;1259}1260return MAV_RESULT_ACCEPTED;1261}1262#endif12631264// this is called on receipt of a MANUAL_CONTROL packet and is1265// expected to call manual_override to override RC input on desired1266// axes.1267void GCS_MAVLINK_Plane::handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow)1268{1269manual_override(plane.channel_roll, packet.y, 1000, 2000, tnow);1270manual_override(plane.channel_pitch, packet.x, 1000, 2000, tnow, true);1271manual_override(plane.channel_throttle, packet.z, 0, 1000, tnow);1272manual_override(plane.channel_rudder, packet.r, 1000, 2000, tnow);1273}12741275void GCS_MAVLINK_Plane::handle_message(const mavlink_message_t &msg)1276{1277switch (msg.msgid) {12781279case MAVLINK_MSG_ID_TERRAIN_DATA:1280case MAVLINK_MSG_ID_TERRAIN_CHECK:1281#if AP_TERRAIN_AVAILABLE1282plane.terrain.handle_data(chan, msg);1283#endif1284break;12851286case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:1287handle_set_attitude_target(msg);1288break;12891290case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:1291handle_set_position_target_local_ned(msg);1292break;12931294case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:1295handle_set_position_target_global_int(msg);1296break;12971298default:1299GCS_MAVLINK::handle_message(msg);1300break;1301} // end switch1302} // end handle mavlink13031304void GCS_MAVLINK_Plane::handle_set_attitude_target(const mavlink_message_t &msg)1305{1306// Only allow companion computer (or other external controller) to1307// control attitude in GUIDED mode. We DON'T want external control1308// in e.g., RTL, CICLE. Specifying a single mode for companion1309// computer control is more safe (even more so when using1310// FENCE_ACTION = 4 for geofence failures).1311if (plane.control_mode != &plane.mode_guided) { // don't screw up failsafes1312return;1313}13141315mavlink_set_attitude_target_t att_target;1316mavlink_msg_set_attitude_target_decode(&msg, &att_target);13171318// Mappings: If any of these bits are set, the corresponding input should be ignored.1319// NOTE, when parsing the bits we invert them for easier interpretation but transport has them inverted1320// bit 1: body roll rate1321// bit 2: body pitch rate1322// bit 3: body yaw rate1323// bit 4: unknown1324// bit 5: unknown1325// bit 6: reserved1326// bit 7: throttle1327// bit 8: attitude13281329// if not setting all Quaternion values, use _rate flags to indicate which fields.13301331// Extract the Euler roll angle from the Quaternion.1332Quaternion q(att_target.q[0], att_target.q[1],1333att_target.q[2], att_target.q[3]);13341335// NOTE: att_target.type_mask is inverted for easier interpretation1336att_target.type_mask = att_target.type_mask ^ 0xFF;13371338uint8_t attitude_mask = att_target.type_mask & 0b10000111; // q plus rpy13391340uint32_t now = AP_HAL::millis();1341if ((attitude_mask & 0b10000001) || // partial, including roll1342(attitude_mask == 0b10000000)) { // all angles1343plane.guided_state.forced_rpy_cd.x = degrees(q.get_euler_roll()) * 100.0f;13441345// Update timer for external roll to the nav control1346plane.guided_state.last_forced_rpy_ms.x = now;1347}13481349if ((attitude_mask & 0b10000010) || // partial, including pitch1350(attitude_mask == 0b10000000)) { // all angles1351plane.guided_state.forced_rpy_cd.y = degrees(q.get_euler_pitch()) * 100.0f;13521353// Update timer for external pitch to the nav control1354plane.guided_state.last_forced_rpy_ms.y = now;1355}13561357if ((attitude_mask & 0b10000100) || // partial, including yaw1358(attitude_mask == 0b10000000)) { // all angles1359plane.guided_state.forced_rpy_cd.z = degrees(q.get_euler_yaw()) * 100.0f;13601361// Update timer for external yaw to the nav control1362plane.guided_state.last_forced_rpy_ms.z = now;1363}1364if (att_target.type_mask & 0b01000000) { // throttle1365plane.guided_state.forced_throttle = att_target.thrust * 100.0f;13661367// Update timer for external throttle1368plane.guided_state.last_forced_throttle_ms = now;1369}1370}13711372void GCS_MAVLINK_Plane::handle_set_position_target_local_ned(const mavlink_message_t &msg)1373{1374// decode packet1375mavlink_set_position_target_local_ned_t packet;1376mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);13771378// exit if vehicle is not in Guided mode1379if (plane.control_mode != &plane.mode_guided) {1380return;1381}13821383// only local moves for now1384if (packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED) {1385return;1386}13871388// just do altitude for now1389plane.next_WP_loc.alt += -packet.z*100.0;1390gcs().send_text(MAV_SEVERITY_INFO, "Change alt to %.1f",1391(double)((plane.next_WP_loc.alt - plane.home.alt)*0.01));1392}13931394void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_message_t &msg)1395{1396// Only want to allow companion computer position control when1397// in a certain mode to avoid inadvertently sending these1398// kinds of commands when the autopilot is responding to problems1399// in modes such as RTL, CIRCLE, etc. Specifying ONLY one mode1400// for companion computer control is more safe (provided1401// one uses the FENCE_ACTION = 4 (RTL) for geofence failures).1402if (plane.control_mode != &plane.mode_guided) {1403//don't screw up failsafes1404return;1405}14061407mavlink_set_position_target_global_int_t pos_target;1408mavlink_msg_set_position_target_global_int_decode(&msg, &pos_target);14091410Location::AltFrame frame;1411if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)pos_target.coordinate_frame, frame)) {1412gcs().send_text(MAV_SEVERITY_WARNING, "Invalid coord frame in SET_POSTION_TARGET_GLOBAL_INT");1413// Even though other parts of the command may be valid, reject the whole thing.1414return;1415}14161417// Unexpectedly, the mask is expecting "ones" for dimensions that should1418// be IGNORNED rather than INCLUDED. See mavlink documentation of the1419// SET_POSITION_TARGET_GLOBAL_INT message, type_mask field.1420const uint16_t alt_mask = 0b1111111111111011; // (z mask at bit 3)14211422AP_Mission::Mission_Command cmd = {0};14231424if (pos_target.type_mask & alt_mask)1425{1426const int32_t alt_cm = pos_target.alt * 100;1427cmd.content.location.set_alt_cm(alt_cm, frame);1428handle_change_alt_request(cmd);1429}1430}14311432MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_int_t &packet)1433{1434const MAV_RESULT result = GCS_MAVLINK::handle_command_do_set_mission_current(packet);1435if (result != MAV_RESULT_ACCEPTED) {1436return result;1437}14381439// if you change this you must change handle_mission_set_current1440plane.auto_state.next_wp_crosstrack = false;1441if (plane.control_mode == &plane.mode_auto && plane.mission.state() == AP_Mission::MISSION_STOPPED) {1442plane.mission.resume();1443}14441445return result;1446}14471448#if AP_MAVLINK_MISSION_SET_CURRENT_ENABLED1449void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg)1450{1451// if you change this you must change handle_command_do_set_mission_current1452plane.auto_state.next_wp_crosstrack = false;1453GCS_MAVLINK::handle_mission_set_current(mission, msg);1454if (plane.control_mode == &plane.mode_auto && plane.mission.state() == AP_Mission::MISSION_STOPPED) {1455plane.mission.resume();1456}1457}1458#endif14591460uint64_t GCS_MAVLINK_Plane::capabilities() const1461{1462return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |1463MAV_PROTOCOL_CAPABILITY_COMMAND_INT |1464MAV_PROTOCOL_CAPABILITY_MISSION_INT |1465MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |1466MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |1467#if AP_TERRAIN_AVAILABLE1468(plane.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |1469#endif1470GCS_MAVLINK::capabilities());1471}14721473#if HAL_HIGH_LATENCY2_ENABLED1474int16_t GCS_MAVLINK_Plane::high_latency_target_altitude() const1475{1476AP_AHRS &ahrs = AP::ahrs();1477Location global_position_current;1478UNUSED_RESULT(ahrs.get_location(global_position_current));14791480#if HAL_QUADPLANE_ENABLED1481const QuadPlane &quadplane = plane.quadplane;1482//return units are m1483if (quadplane.show_vtol_view()) {1484return (plane.control_mode != &plane.mode_qstabilize) ? 0.01 * (global_position_current.alt + quadplane.pos_control->get_pos_error_z_cm()) : 0;1485}1486#endif1487return 0.01 * (global_position_current.alt + plane.calc_altitude_error_cm());1488}14891490uint8_t GCS_MAVLINK_Plane::high_latency_tgt_heading() const1491{1492// return units are deg/21493#if HAL_QUADPLANE_ENABLED1494const QuadPlane &quadplane = plane.quadplane;1495if (quadplane.show_vtol_view()) {1496const Vector3f &targets = quadplane.attitude_control->get_att_target_euler_cd();1497return ((uint16_t)(targets.z * 0.01)) / 2;1498}1499#endif1500const AP_Navigation *nav_controller = plane.nav_controller;1501// need to convert -18000->18000 to 0->360/21502return wrap_360_cd(nav_controller->target_bearing_cd() ) / 200;1503}15041505// return units are dm1506uint16_t GCS_MAVLINK_Plane::high_latency_tgt_dist() const1507{1508#if HAL_QUADPLANE_ENABLED1509const QuadPlane &quadplane = plane.quadplane;1510if (quadplane.show_vtol_view()) {1511bool wp_nav_valid = quadplane.using_wp_nav();1512return (wp_nav_valid ? MIN(quadplane.wp_nav->get_wp_distance_to_destination(), UINT16_MAX) : 0) / 10;1513}1514#endif15151516return MIN(plane.auto_state.wp_distance, UINT16_MAX) / 10;1517}15181519uint8_t GCS_MAVLINK_Plane::high_latency_tgt_airspeed() const1520{1521// return units are m/s*51522return plane.target_airspeed_cm * 0.05;1523}15241525uint8_t GCS_MAVLINK_Plane::high_latency_wind_speed() const1526{1527Vector3f wind;1528wind = AP::ahrs().wind_estimate();15291530// return units are m/s*51531return MIN(wind.length() * 5, UINT8_MAX);1532}15331534uint8_t GCS_MAVLINK_Plane::high_latency_wind_direction() const1535{1536const Vector3f wind = AP::ahrs().wind_estimate();15371538// return units are deg/21539// need to convert -180->180 to 0->360/21540return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;1541}1542#endif // HAL_HIGH_LATENCY2_ENABLED15431544MAV_VTOL_STATE GCS_MAVLINK_Plane::vtol_state() const1545{1546#if !HAL_QUADPLANE_ENABLED1547return MAV_VTOL_STATE_UNDEFINED;1548#else1549if (!plane.quadplane.available()) {1550return MAV_VTOL_STATE_UNDEFINED;1551}15521553return plane.quadplane.transition->get_mav_vtol_state();1554#endif1555};15561557MAV_LANDED_STATE GCS_MAVLINK_Plane::landed_state() const1558{1559if (plane.is_flying()) {1560// note that Q-modes almost always consider themselves as flying1561return MAV_LANDED_STATE_IN_AIR;1562}15631564return MAV_LANDED_STATE_ON_GROUND;1565}15661567// Send the mode with the given index (not mode number!) return the total number of modes1568// Index starts at 11569uint8_t GCS_MAVLINK_Plane::send_available_mode(uint8_t index) const1570{1571// Fixed wing modes1572const Mode* fw_modes[] {1573&plane.mode_manual,1574&plane.mode_circle,1575&plane.mode_stabilize,1576&plane.mode_training,1577&plane.mode_acro,1578&plane.mode_fbwa,1579&plane.mode_fbwb,1580&plane.mode_cruise,1581&plane.mode_autotune,1582&plane.mode_auto,1583&plane.mode_rtl,1584&plane.mode_loiter,1585#if HAL_ADSB_ENABLED1586&plane.mode_avoidADSB,1587#endif1588&plane.mode_guided,1589&plane.mode_initializing,1590&plane.mode_takeoff,1591#if HAL_SOARING_ENABLED1592&plane.mode_thermal,1593#endif1594#if MODE_AUTOLAND_ENABLED1595&plane.mode_autoland,1596#endif1597};15981599const uint8_t fw_mode_count = ARRAY_SIZE(fw_modes);16001601// Fixedwing modes are always present1602uint8_t mode_count = fw_mode_count;16031604#if HAL_QUADPLANE_ENABLED1605// Quadplane modes1606const Mode* q_modes[] {1607&plane.mode_qstabilize,1608&plane.mode_qhover,1609&plane.mode_qloiter,1610&plane.mode_qland,1611&plane.mode_qrtl,1612&plane.mode_qacro,1613&plane.mode_loiter_qland,1614#if QAUTOTUNE_ENABLED1615&plane.mode_qautotune,1616#endif1617};16181619// Quadplane modes must be enabled1620if (plane.quadplane.available()) {1621mode_count += ARRAY_SIZE(q_modes);1622}1623#endif // HAL_QUADPLANE_ENABLED162416251626// Convert to zero indexed1627const uint8_t index_zero = index - 1;1628if (index_zero >= mode_count) {1629// Mode does not exist!?1630return mode_count;1631}16321633// Ask the mode for its name and number1634const char* name;1635uint8_t mode_number;16361637if (index_zero < fw_mode_count) {1638// A fixedwing mode1639name = fw_modes[index_zero]->name();1640mode_number = (uint8_t)fw_modes[index_zero]->mode_number();16411642} else {1643#if HAL_QUADPLANE_ENABLED1644// A Quadplane mode1645const uint8_t q_index = index_zero - fw_mode_count;1646name = q_modes[q_index]->name();1647mode_number = (uint8_t)q_modes[q_index]->mode_number();1648#else1649// Should not endup here1650return mode_count;1651#endif1652}16531654mavlink_msg_available_modes_send(1655chan,1656mode_count,1657index,1658MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,1659mode_number,16600, // MAV_MODE_PROPERTY bitmask1661name1662);16631664return mode_count;1665}166616671668