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/ArduSub/GCS_MAVLink_Sub.cpp
Views: 1798
#include "Sub.h"12#include "GCS_MAVLink_Sub.h"3#include <AP_RPM/AP_RPM_config.h>45MAV_TYPE GCS_Sub::frame_type() const6{7return MAV_TYPE_SUBMARINE;8}910MAV_MODE GCS_MAVLINK_Sub::base_mode() const11{12uint8_t _base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;1314// work out the base_mode. This value is not very useful15// for APM, but we calculate it as best we can so a generic16// MAVLink enabled ground station can work out something about17// what the MAV is up to. The actual bit values are highly18// ambiguous for most of the APM flight modes. In practice, you19// only get useful information from the custom_mode, which maps to20// the APM flight mode and has a well defined meaning in the21// ArduPlane documentation22switch (sub.control_mode) {23case Mode::Number::AUTO:24case Mode::Number::GUIDED:25case Mode::Number::CIRCLE:26case Mode::Number::POSHOLD:27_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;28// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what29// APM does in any mode, as that is defined as "system finds its own goal30// positions", which APM does not currently do31break;32default:33break;34}3536// all modes except INITIALISING have some form of manual37// override if stick mixing is enabled38_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;3940if (sub.motors.armed()) {41_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;42}4344// indicate we have set a custom mode45_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;4647return (MAV_MODE)_base_mode;48}4950uint32_t GCS_Sub::custom_mode() const51{52return (uint32_t)sub.control_mode;53}5455MAV_STATE GCS_MAVLINK_Sub::vehicle_system_status() const56{57// set system as critical if any failsafe have triggered58if (sub.any_failsafe_triggered()) {59return MAV_STATE_CRITICAL;60}6162if (sub.motors.armed()) {63return MAV_STATE_ACTIVE;64}65if (!sub.ap.initialised) {66return MAV_STATE_BOOT;67}6869return MAV_STATE_STANDBY;70}7172void GCS_MAVLINK_Sub::send_banner()73{74GCS_MAVLINK::send_banner();75send_text(MAV_SEVERITY_INFO, "Frame: %s", sub.motors.get_frame_string());76}7778void GCS_MAVLINK_Sub::send_nav_controller_output() const79{80const Vector3f &targets = sub.attitude_control.get_att_target_euler_cd();81mavlink_msg_nav_controller_output_send(82chan,83targets.x * 1.0e-2f,84targets.y * 1.0e-2f,85targets.z * 1.0e-2f,86sub.wp_nav.get_wp_bearing_to_destination() * 1.0e-2f,87MIN(sub.wp_nav.get_wp_distance_to_destination() * 1.0e-2f, UINT16_MAX),88sub.pos_control.get_pos_error_z_cm() * 1.0e-2f,890,900);91}9293int16_t GCS_MAVLINK_Sub::vfr_hud_throttle() const94{95return (int16_t)(sub.motors.get_throttle() * 100);96}9798float GCS_MAVLINK_Sub::vfr_hud_alt() const99{100return sub.get_alt_msl();101}102103// Work around to get temperature sensor data out104void GCS_MAVLINK_Sub::send_scaled_pressure3()105{106#if AP_TEMPERATURE_SENSOR_ENABLED107float temperature;108if (!sub.temperature_sensor.get_temperature(temperature)) {109return;110}111mavlink_msg_scaled_pressure3_send(112chan,113AP_HAL::millis(),1140,1150,116temperature * 100,1170); // TODO: use differential pressure temperature118#endif119}120121bool GCS_MAVLINK_Sub::send_info()122{123// Just do this all at once, hopefully the hard-wire telemetry requirement means this is ok124// Name is char[10]125CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);126send_named_float("CamTilt",1271 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_tilt) / 2.0f + 0.5f));128129CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);130send_named_float("CamPan",1311 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_pan) / 2.0f + 0.5f));132133CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);134send_named_float("TetherTrn",135sub.quarter_turn_count/4);136137CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);138send_named_float("Lights1",139SRV_Channels::get_output_norm(SRV_Channel::k_rcin9) / 2.0f + 0.5f);140141CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);142send_named_float("Lights2",143SRV_Channels::get_output_norm(SRV_Channel::k_rcin10) / 2.0f + 0.5f);144145CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);146send_named_float("PilotGain", sub.gain);147148CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);149send_named_float("InputHold", sub.input_hold_engaged);150151CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);152send_named_float("RollPitch", sub.roll_pitch_flag);153154CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);155send_named_float("RFTarget", sub.mode_surftrak.get_rangefinder_target_cm() * 0.01f);156157return true;158}159160/*161send PID tuning message162*/163void GCS_MAVLINK_Sub::send_pid_tuning()164{165const Parameters &g = sub.g;166AP_AHRS &ahrs = AP::ahrs();167AC_AttitudeControl_Sub &attitude_control = sub.attitude_control;168169const Vector3f &gyro = ahrs.get_gyro();170if (g.gcs_pid_mask & 1) {171const AP_PIDInfo &pid_info = attitude_control.get_rate_roll_pid().get_pid_info();172mavlink_msg_pid_tuning_send(chan, PID_TUNING_ROLL,173pid_info.target*0.01f,174degrees(gyro.x),175pid_info.FF*0.01f,176pid_info.P*0.01f,177pid_info.I*0.01f,178pid_info.D*0.01f,179pid_info.slew_rate,180pid_info.Dmod);181if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {182return;183}184}185if (g.gcs_pid_mask & 2) {186const AP_PIDInfo &pid_info = attitude_control.get_rate_pitch_pid().get_pid_info();187mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,188pid_info.target*0.01f,189degrees(gyro.y),190pid_info.FF*0.01f,191pid_info.P*0.01f,192pid_info.I*0.01f,193pid_info.D*0.01f,194pid_info.slew_rate,195pid_info.Dmod);196if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {197return;198}199}200if (g.gcs_pid_mask & 4) {201const AP_PIDInfo &pid_info = attitude_control.get_rate_yaw_pid().get_pid_info();202mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW,203pid_info.target*0.01f,204degrees(gyro.z),205pid_info.FF*0.01f,206pid_info.P*0.01f,207pid_info.I*0.01f,208pid_info.D*0.01f,209pid_info.slew_rate,210pid_info.Dmod);211if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {212return;213}214}215if (g.gcs_pid_mask & 8) {216const AP_PIDInfo &pid_info = sub.pos_control.get_accel_z_pid().get_pid_info();217mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,218pid_info.target*0.01f,219-(ahrs.get_accel_ef().z + GRAVITY_MSS),220pid_info.FF*0.01f,221pid_info.P*0.01f,222pid_info.I*0.01f,223pid_info.D*0.01f,224pid_info.slew_rate,225pid_info.Dmod);226if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {227return;228}229}230}231232uint8_t GCS_MAVLINK_Sub::sysid_my_gcs() const233{234return sub.g.sysid_my_gcs;235}236237bool GCS_Sub::vehicle_initialised() const {238return sub.ap.initialised;239}240241// try to send a message, return false if it won't fit in the serial tx buffer242bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)243{244switch (id) {245246case MSG_NAMED_FLOAT:247send_info();248break;249250#if AP_TERRAIN_AVAILABLE251case MSG_TERRAIN_REQUEST:252CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);253sub.terrain.send_request(chan);254break;255case MSG_TERRAIN_REPORT:256CHECK_PAYLOAD_SIZE(TERRAIN_REPORT);257sub.terrain.send_report(chan);258break;259#endif260261default:262return GCS_MAVLINK::try_send_message(id);263}264265return true;266}267268269const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {270// @Param: RAW_SENS271// @DisplayName: Raw sensor stream rate272// @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_PRESSURE, AIRSPEED, and SENSOR_OFFSETS to ground station273// @Units: Hz274// @Range: 0 50275// @Increment: 1276// @RebootRequired: True277// @User: Advanced278AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RAW_SENSORS], 2),279280// @Param: EXT_STAT281// @DisplayName: Extended status stream rate to ground station282// @Description: Stream rate of SYS_STATUS, MEMINFO, MISSION_CURRENT, GPS_RAW_INT, NAV_CONTROLLER_OUTPUT, and LIMITS_STATUS to ground station283// @Units: Hz284// @Range: 0 50285// @Increment: 1286// @RebootRequired: True287// @User: Advanced288AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTENDED_STATUS], 2),289290// @Param: RC_CHAN291// @DisplayName: RC Channel stream rate to ground station292// @Description: Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS_RAW to ground station293// @Units: Hz294// @Range: 0 50295// @Increment: 1296// @RebootRequired: True297// @User: Advanced298AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RC_CHANNELS], 2),299300// @Param: POSITION301// @DisplayName: Position stream rate to ground station302// @Description: Stream rate of GLOBAL_POSITION_INT to ground station303// @Units: Hz304// @Range: 0 50305// @Increment: 1306// @RebootRequired: True307// @User: Advanced308AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_POSITION], 3),309310// @Param: EXTRA1311// @DisplayName: Extra data type 1 stream rate to ground station312// @Description: Stream rate of ATTITUDE and SIMSTATE (SITL only) to ground station313// @Units: Hz314// @Range: 0 50315// @Increment: 1316// @RebootRequired: True317// @User: Advanced318AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA1], 10),319320// @Param: EXTRA2321// @DisplayName: Extra data type 2 stream rate to ground station322// @Description: Stream rate of VFR_HUD to ground station323// @Units: Hz324// @Range: 0 50325// @Increment: 1326// @RebootRequired: True327// @User: Advanced328AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA2], 10),329330// @Param: EXTRA3331// @DisplayName: Extra data type 3 stream rate to ground station332// @Description: Stream rate of AHRS and SYSTEM_TIME to ground station333// @Units: Hz334// @Range: 0 50335// @Increment: 1336// @RebootRequired: True337// @User: Advanced338AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA3], 3),339340// @Param: PARAMS341// @DisplayName: Parameter stream rate to ground station342// @Description: Stream rate of PARAM_VALUE to ground station343// @Units: Hz344// @Range: 0 50345// @Increment: 1346// @RebootRequired: True347// @User: Advanced348AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_PARAMS], 0),349AP_GROUPEND350};351352static const ap_message STREAM_RAW_SENSORS_msgs[] = {353MSG_RAW_IMU,354MSG_SCALED_IMU2,355MSG_SCALED_IMU3,356MSG_SCALED_PRESSURE,357MSG_SCALED_PRESSURE2,358MSG_SCALED_PRESSURE3,359#if AP_AIRSPEED_ENABLED360MSG_AIRSPEED,361#endif362};363static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {364MSG_SYS_STATUS,365MSG_POWER_STATUS,366#if HAL_WITH_MCU_MONITORING367MSG_MCU_STATUS,368#endif369MSG_MEMINFO,370MSG_CURRENT_WAYPOINT,371#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED372MSG_GPS_RAW,373#endif374#if AP_GPS_GPS_RTK_SENDING_ENABLED375MSG_GPS_RTK,376#endif377#if AP_GPS_GPS2_RAW_SENDING_ENABLED378MSG_GPS2_RAW,379#endif380#if AP_GPS_GPS2_RTK_SENDING_ENABLED381MSG_GPS2_RTK,382#endif383MSG_NAV_CONTROLLER_OUTPUT,384#if AP_FENCE_ENABLED385MSG_FENCE_STATUS,386#endif387MSG_NAMED_FLOAT388};389static const ap_message STREAM_POSITION_msgs[] = {390MSG_LOCATION,391MSG_LOCAL_POSITION392};393static const ap_message STREAM_RC_CHANNELS_msgs[] = {394MSG_SERVO_OUTPUT_RAW,395MSG_RC_CHANNELS,396#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED397MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection398#endif399};400static const ap_message STREAM_EXTRA1_msgs[] = {401MSG_ATTITUDE,402#if AP_SIM_ENABLED403MSG_SIMSTATE,404#endif405MSG_AHRS2,406MSG_PID_TUNING407};408static const ap_message STREAM_EXTRA2_msgs[] = {409MSG_VFR_HUD410};411static const ap_message STREAM_EXTRA3_msgs[] = {412MSG_AHRS,413MSG_SYSTEM_TIME,414#if AP_RANGEFINDER_ENABLED415MSG_RANGEFINDER,416#endif417MSG_DISTANCE_SENSOR,418#if AP_TERRAIN_AVAILABLE419MSG_TERRAIN_REQUEST,420MSG_TERRAIN_REPORT,421#endif422#if AP_BATTERY_ENABLED423MSG_BATTERY_STATUS,424#endif425#if HAL_MOUNT_ENABLED426MSG_GIMBAL_DEVICE_ATTITUDE_STATUS,427#endif428#if AP_OPTICALFLOW_ENABLED429MSG_OPTICAL_FLOW,430#endif431#if COMPASS_CAL_ENABLED432MSG_MAG_CAL_REPORT,433MSG_MAG_CAL_PROGRESS,434#endif435MSG_EKF_STATUS_REPORT,436MSG_VIBRATION,437#if AP_RPM_ENABLED438MSG_RPM,439#endif440#if HAL_WITH_ESC_TELEM441MSG_ESC_TELEMETRY,442#endif443};444static const ap_message STREAM_PARAMS_msgs[] = {445MSG_NEXT_PARAM,446MSG_AVAILABLE_MODES447};448449const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {450MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),451MAV_STREAM_ENTRY(STREAM_EXTENDED_STATUS),452MAV_STREAM_ENTRY(STREAM_POSITION),453MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),454MAV_STREAM_ENTRY(STREAM_EXTRA1),455MAV_STREAM_ENTRY(STREAM_EXTRA2),456MAV_STREAM_ENTRY(STREAM_EXTRA3),457MAV_STREAM_ENTRY(STREAM_PARAMS),458MAV_STREAM_TERMINATOR // must have this at end of stream_entries459};460461bool GCS_MAVLINK_Sub::handle_guided_request(AP_Mission::Mission_Command &cmd)462{463return sub.do_guided(cmd);464}465466MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro(const mavlink_message_t &msg)467{468if (sub.motors.armed()) {469gcs().send_text(MAV_SEVERITY_INFO, "Disarm before calibration.");470return MAV_RESULT_FAILED;471}472473if (!sub.control_check_barometer()) {474return MAV_RESULT_FAILED;475}476477AP::baro().calibrate(true);478return MAV_RESULT_ACCEPTED;479}480481MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)482{483if (packet.y == 1) {484// compassmot calibration485//result = sub.mavlink_compassmot(chan);486gcs().send_text(MAV_SEVERITY_INFO, "#CompassMot calibration not supported");487return MAV_RESULT_UNSUPPORTED;488}489490return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);491}492493MAV_RESULT GCS_MAVLINK_Sub::handle_command_do_set_roi(const Location &roi_loc)494{495if (!roi_loc.check_latlng()) {496return MAV_RESULT_FAILED;497}498sub.mode_auto.set_auto_yaw_roi(roi_loc);499return MAV_RESULT_ACCEPTED;500}501502MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_do_reposition(const mavlink_command_int_t &packet)503{504const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;505if (!sub.flightmode->in_guided_mode() && !change_modes) {506return MAV_RESULT_DENIED;507}508509// sanity check location510if (!check_latlng(packet.x, packet.y)) {511return MAV_RESULT_DENIED;512}513514Location request_location;515if (!location_from_command_t(packet, request_location)) {516return MAV_RESULT_DENIED;517}518519if (request_location.sanitize(sub.current_loc)) {520// if the location wasn't already sane don't load it521return MAV_RESULT_DENIED; // failed as the location is not valid522}523524// we need to do this first, as we don't want to change the flight mode unless we can also set the target525if (!sub.mode_guided.guided_set_destination(request_location)) {526return MAV_RESULT_FAILED;527}528529if (!sub.flightmode->in_guided_mode()) {530if (!sub.set_mode(Mode::Number::GUIDED, ModeReason::GCS_COMMAND)) {531return MAV_RESULT_FAILED;532}533// the position won't have been loaded if we had to change the flight mode, so load it again534if (!sub.mode_guided.guided_set_destination(request_location)) {535return MAV_RESULT_FAILED;536}537}538539return MAV_RESULT_ACCEPTED;540}541542MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)543{544switch(packet.command) {545546case MAV_CMD_CONDITION_YAW:547return handle_MAV_CMD_CONDITION_YAW(packet);548549case MAV_CMD_DO_CHANGE_SPEED:550return handle_MAV_CMD_DO_CHANGE_SPEED(packet);551552case MAV_CMD_DO_MOTOR_TEST:553return handle_MAV_CMD_DO_MOTOR_TEST(packet);554555case MAV_CMD_DO_REPOSITION:556return handle_command_int_do_reposition(packet);557558case MAV_CMD_MISSION_START:559if (!is_zero(packet.param1) || !is_zero(packet.param2)) {560// first-item/last item not supported561return MAV_RESULT_DENIED;562}563return handle_MAV_CMD_MISSION_START(packet);564565case MAV_CMD_NAV_LOITER_UNLIM:566return handle_MAV_CMD_NAV_LOITER_UNLIM(packet);567568case MAV_CMD_NAV_LAND:569return handle_MAV_CMD_NAV_LAND(packet);570571}572573return GCS_MAVLINK::handle_command_int_packet(packet, msg);574}575576MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_NAV_LOITER_UNLIM(const mavlink_command_int_t &packet)577{578if (!sub.set_mode(Mode::Number::POSHOLD, ModeReason::GCS_COMMAND)) {579return MAV_RESULT_FAILED;580}581return MAV_RESULT_ACCEPTED;582}583584MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_NAV_LAND(const mavlink_command_int_t &packet)585{586if (!sub.set_mode(Mode::Number::SURFACE, ModeReason::GCS_COMMAND)) {587return MAV_RESULT_FAILED;588}589return MAV_RESULT_ACCEPTED;590}591592MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet)593{594// param1 : target angle [0-360]595// param2 : speed during change [deg per second]596// param3 : direction (-1:ccw, +1:cw)597// param4 : relative offset (1) or absolute angle (0)598if ((packet.param1 >= 0.0f) &&599(packet.param1 <= 360.0f) &&600(is_zero(packet.param4) || is_equal(packet.param4,1.0f))) {601sub.mode_auto.set_auto_yaw_look_at_heading(packet.param1, packet.param2, (int8_t)packet.param3, (uint8_t)packet.param4);602return MAV_RESULT_ACCEPTED;603}604return MAV_RESULT_DENIED;605}606607MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet)608{609// param1 : unused610// param2 : new speed in m/s611// param3 : unused612// param4 : unused613if (packet.param2 > 0.0f) {614sub.wp_nav.set_speed_xy(packet.param2 * 100.0f);615return MAV_RESULT_ACCEPTED;616}617return MAV_RESULT_FAILED;618}619620MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet)621{622if (sub.motors.armed() && sub.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {623return MAV_RESULT_ACCEPTED;624}625return MAV_RESULT_FAILED;626}627628MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)629{630// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)631// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)632// param3 : throttle (range depends upon param2)633// param4 : timeout (in seconds)634if (!sub.handle_do_motor_test(packet)) {635return MAV_RESULT_FAILED;636}637return MAV_RESULT_ACCEPTED;638}639640void GCS_MAVLINK_Sub::handle_message(const mavlink_message_t &msg)641{642switch (msg.msgid) {643644case MAVLINK_MSG_ID_MANUAL_CONTROL: { // MAV ID: 69645if (msg.sysid != sub.g.sysid_my_gcs) {646break; // Only accept control from our gcs647}648mavlink_manual_control_t packet;649mavlink_msg_manual_control_decode(&msg, &packet);650651if (packet.target != sub.g.sysid_this_mav) {652break; // only accept control aimed at us653}654655sub.transform_manual_control_to_rc_override(656packet.x,657packet.y,658packet.z,659packet.r,660packet.buttons,661packet.buttons2,662packet.enabled_extensions,663packet.s,664packet.t,665packet.aux1,666packet.aux2,667packet.aux3,668packet.aux4,669packet.aux5,670packet.aux6671);672673sub.failsafe.last_pilot_input_ms = AP_HAL::millis();674// a RC override message is considered to be a 'heartbeat'675// from the ground station for failsafe purposes676gcs().sysid_myggcs_seen(AP_HAL::millis());677break;678}679680case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: { // MAV ID: 70681if (msg.sysid != sub.g.sysid_my_gcs) {682break; // Only accept control from our gcs683}684685sub.failsafe.last_pilot_input_ms = AP_HAL::millis();686// a RC override message is considered to be a 'heartbeat'687// from the ground station for failsafe purposes688689handle_rc_channels_override(msg);690break;691}692693694case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: { // MAV ID: 82695// decode packet696mavlink_set_attitude_target_t packet;697mavlink_msg_set_attitude_target_decode(&msg, &packet);698699// ensure type_mask specifies to use attitude700// the thrust can be used from the altitude hold701if (packet.type_mask & (1<<6)) {702sub.set_attitude_target_no_gps = {AP_HAL::millis(), packet};703}704705// ensure type_mask specifies to use attitude and thrust706if ((packet.type_mask & ((1<<7)|(1<<6))) != 0) {707break;708}709710// convert thrust to climb rate711packet.thrust = constrain_float(packet.thrust, 0.0f, 1.0f);712float climb_rate_cms = 0.0f;713if (is_equal(packet.thrust, 0.5f)) {714climb_rate_cms = 0.0f;715} else if (packet.thrust > 0.5f) {716// climb at up to WPNAV_SPEED_UP717climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * sub.wp_nav.get_default_speed_up();718} else {719// descend at up to WPNAV_SPEED_DN720climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * sub.wp_nav.get_default_speed_down();721}722sub.mode_guided.guided_set_angle(Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]), climb_rate_cms);723break;724}725726case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: { // MAV ID: 84727// decode packet728mavlink_set_position_target_local_ned_t packet;729mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);730731// exit if vehicle is not in Guided mode or Auto-Guided mode732if ((sub.control_mode != Mode::Number::GUIDED) && !(sub.control_mode == Mode::Number::AUTO && sub.auto_mode == Auto_NavGuided)) {733break;734}735736// check for supported coordinate frames737if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED &&738packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&739packet.coordinate_frame != MAV_FRAME_BODY_NED &&740packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED &&741packet.coordinate_frame != MAV_FRAME_BODY_FRD) {742break;743}744745bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;746bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;747bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;748bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;749bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;750751// prepare position752Vector3f pos_vector;753if (!pos_ignore) {754// convert to cm755pos_vector = Vector3f(packet.x * 100.0f, packet.y * 100.0f, -packet.z * 100.0f);756// rotate from body-frame if necessary757if (packet.coordinate_frame == MAV_FRAME_BODY_NED ||758packet.coordinate_frame == MAV_FRAME_BODY_FRD ||759packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {760sub.rotate_body_frame_to_NE(pos_vector.x, pos_vector.y);761}762// add body offset if necessary763if (packet.coordinate_frame == MAV_FRAME_LOCAL_OFFSET_NED ||764packet.coordinate_frame == MAV_FRAME_BODY_NED ||765packet.coordinate_frame == MAV_FRAME_BODY_FRD ||766packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {767pos_vector += sub.inertial_nav.get_position_neu_cm();768}769}770771// prepare velocity772Vector3f vel_vector;773if (!vel_ignore) {774// convert to cm775vel_vector = Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f);776// rotate from body-frame if necessary777if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_FRD || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {778sub.rotate_body_frame_to_NE(vel_vector.x, vel_vector.y);779}780}781782// prepare yaw783float yaw_cd = 0.0f;784bool yaw_relative = false;785float yaw_rate_cds = 0.0f;786if (!yaw_ignore) {787yaw_cd = ToDeg(packet.yaw) * 100.0f;788yaw_relative = packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED;789}790if (!yaw_rate_ignore) {791yaw_rate_cds = ToDeg(packet.yaw_rate) * 100.0f;792}793794// send request795if (!pos_ignore && !vel_ignore && acc_ignore) {796sub.mode_guided.guided_set_destination_posvel(pos_vector, vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);797} else if (pos_ignore && !vel_ignore && acc_ignore) {798sub.mode_guided.guided_set_velocity(vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);799} else if (!pos_ignore && vel_ignore && acc_ignore) {800sub.mode_guided.guided_set_destination(pos_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);801}802803break;804}805806case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT: { // MAV ID: 86807// decode packet808mavlink_set_position_target_global_int_t packet;809mavlink_msg_set_position_target_global_int_decode(&msg, &packet);810811// exit if vehicle is not in Guided, Auto-Guided, or Depth Hold modes812if ((sub.control_mode != Mode::Number::GUIDED)813&& !(sub.control_mode == Mode::Number::AUTO && sub.auto_mode == Auto_NavGuided)814&& !(sub.control_mode == Mode::Number::ALT_HOLD)) {815break;816}817818bool z_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_Z_IGNORE;819bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;820bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;821bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;822823/*824* for future use:825* bool force = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE;826* bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;827* bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;828*/829830if (!z_ignore && sub.control_mode == Mode::Number::ALT_HOLD) { // Control only target depth when in ALT_HOLD831sub.pos_control.set_pos_desired_z_cm(packet.alt*100);832break;833}834835Vector3f pos_neu_cm; // position (North, East, Up coordinates) in centimeters836837if (!pos_ignore) {838// sanity check location839if (!check_latlng(packet.lat_int, packet.lon_int)) {840break;841}842Location::AltFrame frame;843if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.coordinate_frame, frame)) {844// unknown coordinate frame845break;846}847const Location loc{848packet.lat_int,849packet.lon_int,850int32_t(packet.alt*100),851frame,852};853if (!loc.get_vector_from_origin_NEU(pos_neu_cm)) {854break;855}856}857858if (!pos_ignore && !vel_ignore && acc_ignore) {859sub.mode_guided.guided_set_destination_posvel(pos_neu_cm, Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f));860} else if (pos_ignore && !vel_ignore && acc_ignore) {861sub.mode_guided.guided_set_velocity(Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f));862} else if (!pos_ignore && vel_ignore && acc_ignore) {863sub.mode_guided.guided_set_destination(pos_neu_cm);864}865866break;867}868869case MAVLINK_MSG_ID_TERRAIN_DATA:870case MAVLINK_MSG_ID_TERRAIN_CHECK:871#if AP_TERRAIN_AVAILABLE872sub.terrain.handle_data(chan, msg);873#endif874break;875876// This adds support for leak detectors in a separate enclosure877// connected to a mavlink enabled subsystem878case MAVLINK_MSG_ID_SYS_STATUS: {879uint32_t MAV_SENSOR_WATER = 0x20000000;880mavlink_sys_status_t packet;881mavlink_msg_sys_status_decode(&msg, &packet);882if ((packet.onboard_control_sensors_enabled & MAV_SENSOR_WATER) && !(packet.onboard_control_sensors_health & MAV_SENSOR_WATER)) {883sub.leak_detector.set_detect();884}885}886break;887888default:889GCS_MAVLINK::handle_message(msg);890break;891} // end switch892} // end handle mavlink893894uint64_t GCS_MAVLINK_Sub::capabilities() const895{896return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |897MAV_PROTOCOL_CAPABILITY_MISSION_INT |898MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |899MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |900MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION |901#if AP_TERRAIN_AVAILABLE902(sub.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |903#endif904MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |905GCS_MAVLINK::capabilities()906);907}908909MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_int_t &packet)910{911if (packet.param1 > 0.5f) {912sub.arming.disarm(AP_Arming::Method::TERMINATION);913return MAV_RESULT_ACCEPTED;914}915return MAV_RESULT_FAILED;916}917918int32_t GCS_MAVLINK_Sub::global_position_int_alt() const919{920return static_cast<int32_t>(sub.get_alt_msl() * 1000.0f);921}922923int32_t GCS_MAVLINK_Sub::global_position_int_relative_alt() const924{925return static_cast<int32_t>(sub.get_alt_rel() * 1000.0f);926}927928#if HAL_HIGH_LATENCY2_ENABLED929int16_t GCS_MAVLINK_Sub::high_latency_target_altitude() const930{931AP_AHRS &ahrs = AP::ahrs();932Location global_position_current;933UNUSED_RESULT(ahrs.get_location(global_position_current));934935//return units are m936if (sub.control_mode == Mode::Number::AUTO || sub.control_mode == Mode::Number::GUIDED) {937return 0.01 * (global_position_current.alt + sub.pos_control.get_pos_error_z_cm());938}939return 0;940941}942943uint8_t GCS_MAVLINK_Sub::high_latency_tgt_heading() const944{945// return units are deg/2946if (sub.control_mode == Mode::Number::AUTO || sub.control_mode == Mode::Number::GUIDED) {947// need to convert -18000->18000 to 0->360/2948return wrap_360_cd(sub.wp_nav.get_wp_bearing_to_destination()) / 200;949}950return 0;951}952953uint16_t GCS_MAVLINK_Sub::high_latency_tgt_dist() const954{955// return units are dm956if (sub.control_mode == Mode::Number::AUTO || sub.control_mode == Mode::Number::GUIDED) {957return MIN(sub.wp_nav.get_wp_distance_to_destination() * 0.001, UINT16_MAX);958}959return 0;960}961962uint8_t GCS_MAVLINK_Sub::high_latency_tgt_airspeed() const963{964// return units are m/s*5965if (sub.control_mode == Mode::Number::AUTO || sub.control_mode == Mode::Number::GUIDED) {966return MIN((sub.pos_control.get_vel_desired_cms().length()/100) * 5, UINT8_MAX);967}968return 0;969}970#endif // HAL_HIGH_LATENCY2_ENABLED971972// Send the mode with the given index (not mode number!) return the total number of modes973// Index starts at 1974uint8_t GCS_MAVLINK_Sub::send_available_mode(uint8_t index) const975{976const Mode* modes[] {977&sub.mode_manual,978&sub.mode_stabilize,979&sub.mode_acro,980&sub.mode_althold,981&sub.mode_surftrak,982&sub.mode_poshold,983&sub.mode_auto,984&sub.mode_guided,985&sub.mode_circle,986&sub.mode_surface,987&sub.mode_motordetect,988};989990const uint8_t mode_count = ARRAY_SIZE(modes);991992// Convert to zero indexed993const uint8_t index_zero = index - 1;994if (index_zero >= mode_count) {995// Mode does not exist!?996return mode_count;997}998999// Ask the mode for its name and number1000const char* name = modes[index_zero]->name();1001const uint8_t mode_number = (uint8_t)modes[index_zero]->number();10021003mavlink_msg_available_modes_send(1004chan,1005mode_count,1006index,1007MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,1008mode_number,10090, // MAV_MODE_PROPERTY bitmask1010name1011);10121013return mode_count;1014}101510161017