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/Blimp/GCS_MAVLink_Blimp.cpp
Views: 1798
#include "Blimp.h"12#include "GCS_MAVLink_Blimp.h"3#include <AP_RPM/AP_RPM_config.h>4#include <AP_OpticalFlow/AP_OpticalFlow_config.h>56MAV_TYPE GCS_Blimp::frame_type() const7{8return blimp.get_frame_mav_type();9}1011MAV_MODE GCS_MAVLINK_Blimp::base_mode() const12{13uint8_t _base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;14_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;1516// we are armed if we are not initialising17if (blimp.motors != nullptr && blimp.motors->armed()) {18_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;19}2021// indicate we have set a custom mode22_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;2324return (MAV_MODE)_base_mode;25}2627uint32_t GCS_Blimp::custom_mode() const28{29return (uint32_t)blimp.control_mode;30}3132MAV_STATE GCS_MAVLINK_Blimp::vehicle_system_status() const33{34// set system as critical if any failsafe have triggered35if (blimp.any_failsafe_triggered()) {36return MAV_STATE_CRITICAL;37}3839if (blimp.ap.land_complete) {40return MAV_STATE_STANDBY;41}42if (!blimp.ap.initialised) {43return MAV_STATE_BOOT;44}4546return MAV_STATE_ACTIVE;47}484950void GCS_MAVLINK_Blimp::send_position_target_global_int()51{52Location target;53if (!blimp.flightmode->get_wp(target)) {54return;55}56static constexpr uint16_t POSITION_TARGET_TYPEMASK_LAST_BYTE = 0xF000;57static constexpr uint16_t TYPE_MASK = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |58POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE |59POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE;6061mavlink_msg_position_target_global_int_send(62chan,63AP_HAL::millis(), // time_boot_ms64MAV_FRAME_GLOBAL, // targets are always global altitude65TYPE_MASK, // ignore everything except the x/y/z components66target.lat, // latitude as 1e767target.lng, // longitude as 1e768target.alt * 0.01f, // altitude is sent as a float690.0f, // vx700.0f, // vy710.0f, // vz720.0f, // afx730.0f, // afy740.0f, // afz750.0f, // yaw760.0f); // yaw_rate77}7879void GCS_MAVLINK_Blimp::send_nav_controller_output() const80{8182}8384float GCS_MAVLINK_Blimp::vfr_hud_airspeed() const85{86Vector3f airspeed_vec_bf;87if (AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {88// we are running the EKF3 wind estimation code which can give89// us an airspeed estimate90return airspeed_vec_bf.length();91}92return AP::gps().ground_speed();93}9495int16_t GCS_MAVLINK_Blimp::vfr_hud_throttle() const96{97if (blimp.motors == nullptr) {98return 0;99}100return (int16_t)(blimp.motors->get_throttle() * 100);101}102103/*104send PID tuning message105*/106void GCS_MAVLINK_Blimp::send_pid_tuning()107{108if (blimp.control_mode == Mode::Number::MANUAL || blimp.control_mode == Mode::Number::LAND) {109//No PIDs are used in Manual or Land mode.110return;111}112113static const int8_t axes[] = {114PID_SEND::VELX,115PID_SEND::VELY,116PID_SEND::VELZ,117PID_SEND::VELYAW,118PID_SEND::POSX,119PID_SEND::POSY,120PID_SEND::POSZ,121PID_SEND::POSYAW122};123for (uint8_t i=0; i<ARRAY_SIZE(axes); i++) {124if (!(blimp.g.gcs_pid_mask & (1<<(axes[i]-1)))) {125continue;126}127if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {128return;129}130const AP_PIDInfo *pid_info = nullptr;131switch (axes[i]) {132case PID_SEND::VELX:133pid_info = &blimp.pid_vel_xy.get_pid_info_x();134break;135case PID_SEND::VELY:136pid_info = &blimp.pid_vel_xy.get_pid_info_y();137break;138case PID_SEND::VELZ:139pid_info = &blimp.pid_vel_z.get_pid_info();140break;141case PID_SEND::VELYAW:142pid_info = &blimp.pid_vel_yaw.get_pid_info();143break;144case PID_SEND::POSX:145pid_info = &blimp.pid_pos_xy.get_pid_info_x();146break;147case PID_SEND::POSY:148pid_info = &blimp.pid_pos_xy.get_pid_info_y();149break;150case PID_SEND::POSZ:151pid_info = &blimp.pid_pos_z.get_pid_info();152break;153case PID_SEND::POSYAW:154pid_info = &blimp.pid_pos_yaw.get_pid_info();155break;156default:157continue;158}159if (pid_info != nullptr) {160mavlink_msg_pid_tuning_send(chan,161axes[i],162pid_info->target,163pid_info->actual,164pid_info->FF,165pid_info->P,166pid_info->I,167pid_info->D,168pid_info->slew_rate,169pid_info->Dmod);170}171}172}173174uint8_t GCS_MAVLINK_Blimp::sysid_my_gcs() const175{176return blimp.g.sysid_my_gcs;177}178bool GCS_MAVLINK_Blimp::sysid_enforce() const179{180return blimp.g2.sysid_enforce;181}182183uint32_t GCS_MAVLINK_Blimp::telem_delay() const184{185return (uint32_t)(blimp.g.telem_delay);186}187188bool GCS_Blimp::vehicle_initialised() const189{190return blimp.ap.initialised;191}192193// try to send a message, return false if it wasn't sent194bool GCS_MAVLINK_Blimp::try_send_message(enum ap_message id)195{196switch (id) {197198case MSG_WIND:199CHECK_PAYLOAD_SIZE(WIND);200send_wind();201break;202203case MSG_SERVO_OUT:204case MSG_AOA_SSA:205case MSG_LANDING:206case MSG_ADSB_VEHICLE:207// unused208break;209210default:211return GCS_MAVLINK::try_send_message(id);212}213return true;214}215216217const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {218// @Param: RAW_SENS219// @DisplayName: Raw sensor stream rate220// @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3, AIRSPEED and SENSOR_OFFSETS to ground station221// @Units: Hz222// @Range: 0 10223// @Increment: 1224// @RebootRequired: True225// @User: Advanced226AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 0),227228// @Param: EXT_STAT229// @DisplayName: Extended status stream rate to ground station230// @Description: Stream rate of SYS_STATUS, POWER_STATUS, MCU_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, and FENCE_STATUS to ground station231// @Units: Hz232// @Range: 0 10233// @Increment: 1234// @RebootRequired: True235// @User: Advanced236AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 0),237238// @Param: RC_CHAN239// @DisplayName: RC Channel stream rate to ground station240// @Description: Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS to ground station241// @Units: Hz242// @Range: 0 10243// @Increment: 1244// @RebootRequired: True245// @User: Advanced246AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 0),247248// @Param: RAW_CTRL249// @DisplayName: Unused250// @Description: Unused251// @Units: Hz252// @Range: 0 10253// @Increment: 1254// @RebootRequired: True255// @User: Advanced256AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 0),257258// @Param: POSITION259// @DisplayName: Position stream rate to ground station260// @Description: Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED to ground station261// @Units: Hz262// @Range: 0 10263// @Increment: 1264// @RebootRequired: True265// @User: Advanced266AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 0),267268// @Param: EXTRA1269// @DisplayName: Extra data type 1 stream rate to ground station270// @Description: Stream rate of ATTITUDE, SIMSTATE (SITL only), AHRS2 and PID_TUNING to ground station271// @Units: Hz272// @Range: 0 10273// @Increment: 1274// @RebootRequired: True275// @User: Advanced276AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 0),277278// @Param: EXTRA2279// @DisplayName: Extra data type 2 stream rate to ground station280// @Description: Stream rate of VFR_HUD to ground station281// @Units: Hz282// @Range: 0 10283// @Increment: 1284// @RebootRequired: True285// @User: Advanced286AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 0),287288// @Param: EXTRA3289// @DisplayName: Extra data type 3 stream rate to ground station290// @Description: Stream rate of AHRS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station291// @Units: Hz292// @Range: 0 10293// @Increment: 1294// @RebootRequired: True295// @User: Advanced296AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 0),297298// @Param: PARAMS299// @DisplayName: Parameter stream rate to ground station300// @Description: Stream rate of PARAM_VALUE to ground station301// @Units: Hz302// @Range: 0 10303// @Increment: 1304// @RebootRequired: True305// @User: Advanced306AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 0),307AP_GROUPEND308};309310static const ap_message STREAM_RAW_SENSORS_msgs[] = {311MSG_RAW_IMU,312MSG_SCALED_IMU2,313MSG_SCALED_IMU3,314MSG_SCALED_PRESSURE,315MSG_SCALED_PRESSURE2,316MSG_SCALED_PRESSURE3,317#if AP_AIRSPEED_ENABLED318MSG_AIRSPEED,319#endif320};321static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {322MSG_SYS_STATUS,323MSG_POWER_STATUS,324#if HAL_WITH_MCU_MONITORING325MSG_MCU_STATUS,326#endif327MSG_MEMINFO,328MSG_CURRENT_WAYPOINT, // MISSION_CURRENT329#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED330MSG_GPS_RAW,331#endif332#if AP_GPS_GPS_RTK_SENDING_ENABLED333MSG_GPS_RTK,334#endif335#if AP_GPS_GPS2_RAW_SENDING_ENABLED336MSG_GPS2_RAW,337#endif338#if AP_GPS_GPS2_RTK_SENDING_ENABLED339MSG_GPS2_RTK,340#endif341MSG_NAV_CONTROLLER_OUTPUT,342#if AP_FENCE_ENABLED343MSG_FENCE_STATUS,344#endif345MSG_POSITION_TARGET_GLOBAL_INT,346};347static const ap_message STREAM_POSITION_msgs[] = {348MSG_LOCATION,349MSG_LOCAL_POSITION350};351static const ap_message STREAM_RC_CHANNELS_msgs[] = {352MSG_SERVO_OUTPUT_RAW,353MSG_RC_CHANNELS,354#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED355MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection356#endif357};358static const ap_message STREAM_EXTRA1_msgs[] = {359MSG_ATTITUDE,360#if AP_SIM_ENABLED361MSG_SIMSTATE,362#endif363MSG_AHRS2,364MSG_PID_TUNING // Up to four PID_TUNING messages are sent, depending on GCS_PID_MASK parameter365};366static const ap_message STREAM_EXTRA2_msgs[] = {367MSG_VFR_HUD368};369static const ap_message STREAM_EXTRA3_msgs[] = {370MSG_AHRS,371MSG_SYSTEM_TIME,372MSG_WIND,373#if AP_RANGEFINDER_ENABLED374MSG_RANGEFINDER,375#endif376MSG_DISTANCE_SENSOR,377#if AP_BATTERY_ENABLED378MSG_BATTERY_STATUS,379#endif380#if HAL_MOUNT_ENABLED381MSG_GIMBAL_DEVICE_ATTITUDE_STATUS,382#endif383#if AP_OPTICALFLOW_ENABLED384MSG_OPTICAL_FLOW,385#endif386#if COMPASS_CAL_ENABLED387MSG_MAG_CAL_REPORT,388MSG_MAG_CAL_PROGRESS,389#endif390MSG_EKF_STATUS_REPORT,391MSG_VIBRATION,392#if AP_RPM_ENABLED393MSG_RPM,394#endif395#if HAL_WITH_ESC_TELEM396MSG_ESC_TELEMETRY,397#endif398#if HAL_GENERATOR_ENABLED399MSG_GENERATOR_STATUS,400#endif401};402static const ap_message STREAM_PARAMS_msgs[] = {403MSG_NEXT_PARAM,404MSG_AVAILABLE_MODES405};406static const ap_message STREAM_ADSB_msgs[] = {407MSG_ADSB_VEHICLE,408#if AP_AIS_ENABLED409MSG_AIS_VESSEL,410#endif411};412413const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {414MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),415MAV_STREAM_ENTRY(STREAM_EXTENDED_STATUS),416MAV_STREAM_ENTRY(STREAM_POSITION),417MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),418MAV_STREAM_ENTRY(STREAM_EXTRA1),419MAV_STREAM_ENTRY(STREAM_EXTRA2),420MAV_STREAM_ENTRY(STREAM_EXTRA3),421MAV_STREAM_ENTRY(STREAM_ADSB),422MAV_STREAM_ENTRY(STREAM_PARAMS),423MAV_STREAM_TERMINATOR // must have this at end of stream_entries424};425426void GCS_MAVLINK_Blimp::packetReceived(const mavlink_status_t &status,427const mavlink_message_t &msg)428{429GCS_MAVLINK::packetReceived(status, msg);430}431432bool GCS_MAVLINK_Blimp::params_ready() const433{434if (AP_BoardConfig::in_config_error()) {435// we may never have parameters "initialised" in this case436return true;437}438// if we have not yet initialised (including allocating the motors439// object) we drop this request. That prevents the GCS from getting440// a confusing parameter count during bootup441return blimp.ap.initialised_params;442}443444void GCS_MAVLINK_Blimp::send_banner()445{446GCS_MAVLINK::send_banner();447send_text(MAV_SEVERITY_INFO, "Frame: %s", blimp.get_frame_string());448}449450MAV_RESULT GCS_MAVLINK_Blimp::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)451{452return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);453}454455456MAV_RESULT GCS_MAVLINK_Blimp::handle_command_do_set_roi(const Location &roi_loc)457{458if (!roi_loc.check_latlng()) {459return MAV_RESULT_FAILED;460}461// blimp.flightmode->auto_yaw.set_roi(roi_loc);462return MAV_RESULT_ACCEPTED;463}464465MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_do_reposition(const mavlink_command_int_t &packet)466{467const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;468if (!blimp.flightmode->in_guided_mode() && !change_modes) {469return MAV_RESULT_DENIED;470}471472// sanity check location473if (!check_latlng(packet.x, packet.y)) {474return MAV_RESULT_DENIED;475}476477Location request_location {};478if (!location_from_command_t(packet, request_location)) {479return MAV_RESULT_DENIED;480}481482if (request_location.sanitize(blimp.current_loc)) {483// if the location wasn't already sane don't load it484return MAV_RESULT_DENIED; // failed as the location is not valid485}486487return MAV_RESULT_ACCEPTED;488}489490MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)491{492switch (packet.command) {493case MAV_CMD_DO_REPOSITION:494return handle_command_int_do_reposition(packet);495case MAV_CMD_NAV_TAKEOFF:496return MAV_RESULT_ACCEPTED;497default:498return GCS_MAVLINK::handle_command_int_packet(packet, msg);499}500}501502#if AP_MAVLINK_COMMAND_LONG_ENABLED503bool GCS_MAVLINK_Blimp::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const504{505if (packet_command == MAV_CMD_NAV_TAKEOFF) {506frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;507return true;508}509return GCS_MAVLINK::mav_frame_for_command_long(frame, packet_command);510}511#endif512513void GCS_MAVLINK_Blimp::handle_message(const mavlink_message_t &msg)514{515switch (msg.msgid) {516517case MAVLINK_MSG_ID_TERRAIN_DATA:518case MAVLINK_MSG_ID_TERRAIN_CHECK:519break;520521default:522GCS_MAVLINK::handle_message(msg);523break;524} // end switch525} // end handle mavlink526527528MAV_RESULT GCS_MAVLINK_Blimp::handle_flight_termination(const mavlink_command_int_t &packet)529{530MAV_RESULT result = MAV_RESULT_FAILED;531if (packet.param1 > 0.5f) {532blimp.arming.disarm(AP_Arming::Method::TERMINATION);533result = MAV_RESULT_ACCEPTED;534}535return result;536}537538float GCS_MAVLINK_Blimp::vfr_hud_alt() const539{540if (blimp.g2.dev_options.get() & DevOptionVFR_HUDRelativeAlt) {541// compatibility option for older mavlink-aware devices that542// assume Blimp returns a relative altitude in VFR_HUD.alt543return blimp.current_loc.alt * 0.01f;544}545return GCS_MAVLINK::vfr_hud_alt();546}547548uint64_t GCS_MAVLINK_Blimp::capabilities() const549{550return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |551MAV_PROTOCOL_CAPABILITY_MISSION_INT |552MAV_PROTOCOL_CAPABILITY_COMMAND_INT |553MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |554MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |555MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION |556MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |557GCS_MAVLINK::capabilities());558}559560MAV_LANDED_STATE GCS_MAVLINK_Blimp::landed_state() const561{562if (blimp.ap.land_complete) {563return MAV_LANDED_STATE_ON_GROUND;564}565if (blimp.flightmode->is_landing()) {566return MAV_LANDED_STATE_LANDING;567}568// if (blimp.flightmode->is_taking_off()) {569// return MAV_LANDED_STATE_TAKEOFF;570// }571return MAV_LANDED_STATE_IN_AIR;572}573574void GCS_MAVLINK_Blimp::send_wind() const575{576Vector3f airspeed_vec_bf;577if (!AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {578// if we don't have an airspeed estimate then we don't have a579// valid wind estimate on blimps580return;581}582const Vector3f wind = AP::ahrs().wind_estimate();583mavlink_msg_wind_send(584chan,585degrees(atan2f(-wind.y, -wind.x)),586wind.length(),587wind.z);588}589590#if HAL_HIGH_LATENCY2_ENABLED591uint8_t GCS_MAVLINK_Blimp::high_latency_wind_speed() const592{593Vector3f airspeed_vec_bf;594if (!AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {595// if we don't have an airspeed estimate then we don't have a596// valid wind estimate on blimps597return 0;598}599// return units are m/s*5600const Vector3f wind = AP::ahrs().wind_estimate();601return wind.length() * 5;602}603604uint8_t GCS_MAVLINK_Blimp::high_latency_wind_direction() const605{606Vector3f airspeed_vec_bf;607if (!AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {608// if we don't have an airspeed estimate then we don't have a609// valid wind estimate on blimps610return 0;611}612const Vector3f wind = AP::ahrs().wind_estimate();613// need to convert -180->180 to 0->360/2614return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;615}616#endif // HAL_HIGH_LATENCY2_ENABLED617618// Send the mode with the given index (not mode number!) return the total number of modes619// Index starts at 1620uint8_t GCS_MAVLINK_Blimp::send_available_mode(uint8_t index) const621{622const Mode* modes[] {623&blimp.mode_land,624&blimp.mode_manual,625&blimp.mode_velocity,626&blimp.mode_loiter,627&blimp.mode_rtl,628};629630const uint8_t mode_count = ARRAY_SIZE(modes);631632// Convert to zero indexed633const uint8_t index_zero = index - 1;634if (index_zero >= mode_count) {635// Mode does not exist!?636return mode_count;637}638639// Ask the mode for its name and number640const char* name = modes[index_zero]->name();641const uint8_t mode_number = (uint8_t)modes[index_zero]->number();642643mavlink_msg_available_modes_send(644chan,645mode_count,646index,647MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,648mode_number,6490, // MAV_MODE_PROPERTY bitmask650name651);652653return mode_count;654}655656657