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/AntennaTracker/GCS_MAVLink_Tracker.cpp
Views: 1798
#include "GCS_MAVLink_Tracker.h"1#include "Tracker.h"23MAV_TYPE GCS_Tracker::frame_type() const4{5return MAV_TYPE_ANTENNA_TRACKER;6}78MAV_MODE GCS_MAVLINK_Tracker::base_mode() const9{10uint8_t _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;11// work out the base_mode. This value is not very useful12// for APM, but we calculate it as best we can so a generic13// MAVLink enabled ground station can work out something about14// what the MAV is up to. The actual bit values are highly15// ambiguous for most of the APM flight modes. In practice, you16// only get useful information from the custom_mode, which maps to17// the APM flight mode and has a well defined meaning in the18// ArduPlane documentation19switch (tracker.mode->number()) {20case Mode::Number::MANUAL:21_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;22break;2324case Mode::Number::STOP:25break;2627case Mode::Number::SCAN:28case Mode::Number::SERVOTEST:29case Mode::Number::AUTO:30case Mode::Number::GUIDED:31_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED |32MAV_MODE_FLAG_STABILIZE_ENABLED;33// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what34// APM does in any mode, as that is defined as "system finds its own goal35// positions", which APM does not currently do36break;3738case Mode::Number::INITIALISING:39break;40}4142// we are armed if safety switch is not disarmed43if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED &&44tracker.mode != &tracker.mode_initialising &&45hal.util->get_soft_armed()) {46_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;47}4849return (MAV_MODE)_base_mode;50}5152uint32_t GCS_Tracker::custom_mode() const53{54return (uint32_t)tracker.mode->number();55}5657MAV_STATE GCS_MAVLINK_Tracker::vehicle_system_status() const58{59if (tracker.mode == &tracker.mode_initialising) {60return MAV_STATE_CALIBRATING;61}62return MAV_STATE_ACTIVE;63}6465void GCS_MAVLINK_Tracker::send_nav_controller_output() const66{67float alt_diff = (tracker.g.alt_source == ALT_SOURCE_BARO) ? tracker.nav_status.alt_difference_baro : tracker.nav_status.alt_difference_gps;6869mavlink_msg_nav_controller_output_send(70chan,710,72tracker.nav_status.pitch,73tracker.nav_status.bearing,74tracker.nav_status.bearing,75MIN(tracker.nav_status.distance, UINT16_MAX),76alt_diff,770,780);79}8081void GCS_MAVLINK_Tracker::handle_set_attitude_target(const mavlink_message_t &msg)82{83// decode packet84mavlink_set_attitude_target_t packet;85mavlink_msg_set_attitude_target_decode(&msg, &packet);8687// exit if vehicle is not in Guided mode88if (tracker.mode != &tracker.mode_guided) {89return;90}9192// sanity checks:93if (!is_zero(packet.body_roll_rate)) {94return;95}96if (!(packet.type_mask & (1<<0))) {97// not told to ignore body roll rate98return;99}100if (!(packet.type_mask & (1<<6))) {101// not told to ignore throttle102return;103}104if (packet.type_mask & (1<<7)) {105// told to ignore attitude (we don't allow continuous motion yet)106return;107}108if ((packet.type_mask & (1<<3)) && (packet.type_mask&(1<<4))) {109// told to ignore both pitch and yaw rates - nothing to do?!110return;111}112113const bool use_yaw_rate = !(packet.type_mask & (1<<2));114115tracker.mode_guided.set_angle(116Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]),117use_yaw_rate,118packet.body_yaw_rate);119}120121/*122send PID tuning message123*/124void GCS_MAVLINK_Tracker::send_pid_tuning()125{126const Parameters &g = tracker.g;127128// Pitch PID129if (g.gcs_pid_mask & 1) {130const AP_PIDInfo *pid_info = &g.pidPitch2Srv.get_pid_info();131mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,132pid_info->target,133pid_info->actual,134pid_info->FF,135pid_info->P,136pid_info->I,137pid_info->D,138pid_info->slew_rate,139pid_info->Dmod);140if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {141return;142}143}144145// Yaw PID146if (g.gcs_pid_mask & 2) {147const AP_PIDInfo *pid_info = &g.pidYaw2Srv.get_pid_info();148mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW,149pid_info->target,150pid_info->actual,151pid_info->FF,152pid_info->P,153pid_info->I,154pid_info->D,155pid_info->slew_rate,156pid_info->Dmod);157if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {158return;159}160}161}162163/*164default stream rates to 1Hz165*/166const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {167// @Param: RAW_SENS168// @DisplayName: Raw sensor stream rate169// @Description: Raw sensor stream rate to ground station170// @Units: Hz171// @Range: 0 50172// @Increment: 1173// @RebootRequired: True174// @User: Advanced175AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1),176177// @Param: EXT_STAT178// @DisplayName: Extended status stream rate to ground station179// @Description: Extended status stream rate to ground station180// @Units: Hz181// @Range: 0 50182// @Increment: 1183// @RebootRequired: True184// @User: Advanced185AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1),186187// @Param: RC_CHAN188// @DisplayName: RC Channel stream rate to ground station189// @Description: RC Channel stream rate to ground station190// @Units: Hz191// @Range: 0 50192// @Increment: 1193// @RebootRequired: True194// @User: Advanced195AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1),196197// @Param: RAW_CTRL198// @DisplayName: Raw Control stream rate to ground station199// @Description: Raw Control stream rate to ground station200// @Units: Hz201// @Range: 0 50202// @Increment: 1203// @RebootRequired: True204// @User: Advanced205AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1),206207// @Param: POSITION208// @DisplayName: Position stream rate to ground station209// @Description: Position stream rate to ground station210// @Units: Hz211// @Range: 0 50212// @Increment: 1213// @RebootRequired: True214// @User: Advanced215AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 1),216217// @Param: EXTRA1218// @DisplayName: Extra data type 1 stream rate to ground station219// @Description: Extra data type 1 stream rate to ground station220// @Units: Hz221// @Range: 0 50222// @Increment: 1223// @RebootRequired: True224// @User: Advanced225AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1),226227// @Param: EXTRA2228// @DisplayName: Extra data type 2 stream rate to ground station229// @Description: Extra data type 2 stream rate to ground station230// @Units: Hz231// @Range: 0 50232// @Increment: 1233// @RebootRequired: True234// @User: Advanced235AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1),236237// @Param: EXTRA3238// @DisplayName: Extra data type 3 stream rate to ground station239// @Description: Extra data type 3 stream rate to ground station240// @Units: Hz241// @Range: 0 50242// @Increment: 1243// @RebootRequired: True244// @User: Advanced245AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1),246247// @Param: PARAMS248// @DisplayName: Parameter stream rate to ground station249// @Description: Parameter stream rate to ground station250// @Units: Hz251// @Range: 0 50252// @Increment: 1253// @RebootRequired: True254// @User: Advanced255AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10),256AP_GROUPEND257};258259static const ap_message STREAM_RAW_SENSORS_msgs[] = {260MSG_RAW_IMU,261MSG_SCALED_IMU2,262MSG_SCALED_IMU3,263MSG_SCALED_PRESSURE,264MSG_SCALED_PRESSURE2,265MSG_SCALED_PRESSURE3,266#if AP_AIRSPEED_ENABLED267MSG_AIRSPEED,268#endif269};270static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {271MSG_SYS_STATUS,272MSG_POWER_STATUS,273#if HAL_WITH_MCU_MONITORING274MSG_MCU_STATUS,275#endif276MSG_MEMINFO,277MSG_NAV_CONTROLLER_OUTPUT,278#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED279MSG_GPS_RAW,280#endif281#if AP_GPS_GPS_RTK_SENDING_ENABLED282MSG_GPS_RTK,283#endif284#if AP_GPS_GPS2_RAW_SENDING_ENABLED285MSG_GPS2_RAW,286#endif287#if AP_GPS_GPS2_RTK_SENDING_ENABLED288MSG_GPS2_RTK,289#endif290};291static const ap_message STREAM_POSITION_msgs[] = {292MSG_LOCATION,293MSG_LOCAL_POSITION294};295static const ap_message STREAM_RAW_CONTROLLER_msgs[] = {296MSG_SERVO_OUTPUT_RAW,297};298static const ap_message STREAM_RC_CHANNELS_msgs[] = {299MSG_RC_CHANNELS,300#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED301MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection302#endif303};304static const ap_message STREAM_EXTRA1_msgs[] = {305MSG_ATTITUDE,306MSG_PID_TUNING,307};308static const ap_message STREAM_EXTRA3_msgs[] = {309MSG_AHRS,310#if AP_SIM_ENABLED311MSG_SIMSTATE,312#endif313MSG_SYSTEM_TIME,314MSG_AHRS2,315#if COMPASS_CAL_ENABLED316MSG_MAG_CAL_REPORT,317MSG_MAG_CAL_PROGRESS,318#endif319MSG_EKF_STATUS_REPORT,320MSG_BATTERY_STATUS,321};322static const ap_message STREAM_PARAMS_msgs[] = {323MSG_NEXT_PARAM,324MSG_AVAILABLE_MODES325};326327const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {328MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),329MAV_STREAM_ENTRY(STREAM_EXTENDED_STATUS),330MAV_STREAM_ENTRY(STREAM_POSITION),331MAV_STREAM_ENTRY(STREAM_RAW_CONTROLLER),332MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),333MAV_STREAM_ENTRY(STREAM_EXTRA1),334MAV_STREAM_ENTRY(STREAM_EXTRA3),335MAV_STREAM_ENTRY(STREAM_PARAMS),336MAV_STREAM_TERMINATOR // must have this at end of stream_entries337};338339/*340We eavesdrop on MAVLINK_MSG_ID_GLOBAL_POSITION_INT and341MAVLINK_MSG_ID_SCALED_PRESSUREs342*/343void GCS_MAVLINK_Tracker::packetReceived(const mavlink_status_t &status,344const mavlink_message_t &msg)345{346// return immediately if sysid doesn't match our target sysid347if ((tracker.g.sysid_target != 0) && (tracker.g.sysid_target != msg.sysid)) {348GCS_MAVLINK::packetReceived(status, msg);349return;350}351352switch (msg.msgid) {353case MAVLINK_MSG_ID_HEARTBEAT:354{355mavlink_check_target(msg);356break;357}358359case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:360{361// decode362mavlink_global_position_int_t packet;363mavlink_msg_global_position_int_decode(&msg, &packet);364tracker.tracking_update_position(packet);365break;366}367368case MAVLINK_MSG_ID_SCALED_PRESSURE:369{370// decode371mavlink_scaled_pressure_t packet;372mavlink_msg_scaled_pressure_decode(&msg, &packet);373tracker.tracking_update_pressure(packet);374break;375}376}377GCS_MAVLINK::packetReceived(status, msg);378}379380// locks onto a particular target sysid and sets it's position data stream to at least 1hz381void GCS_MAVLINK_Tracker::mavlink_check_target(const mavlink_message_t &msg)382{383// exit immediately if the target has already been set384if (tracker.target_set) {385return;386}387388// decode389mavlink_heartbeat_t packet;390mavlink_msg_heartbeat_decode(&msg, &packet);391392// exit immediately if this is not a vehicle we would track393if ((packet.type == MAV_TYPE_ANTENNA_TRACKER) ||394(packet.type == MAV_TYPE_GCS) ||395(packet.type == MAV_TYPE_ONBOARD_CONTROLLER) ||396(packet.type == MAV_TYPE_GIMBAL)) {397return;398}399400// set our sysid to the target, this ensures we lock onto a single vehicle401if (tracker.g.sysid_target == 0) {402tracker.g.sysid_target.set(msg.sysid);403}404405// send data stream request to target on all channels406// Note: this doesn't check success for all sends meaning it's not guaranteed the vehicle's positions will be sent at 1hz407tracker.gcs().request_datastream_position(msg.sysid, msg.compid);408tracker.gcs().request_datastream_airpressure(msg.sysid, msg.compid);409410// flag target has been set411tracker.target_set = true;412}413414uint8_t GCS_MAVLINK_Tracker::sysid_my_gcs() const415{416return tracker.g.sysid_my_gcs;417}418419MAV_RESULT GCS_MAVLINK_Tracker::_handle_command_preflight_calibration_baro(const mavlink_message_t &msg)420{421MAV_RESULT ret = GCS_MAVLINK::_handle_command_preflight_calibration_baro(msg);422if (ret == MAV_RESULT_ACCEPTED) {423// zero the altitude difference on next baro update424tracker.nav_status.need_altitude_calibration = true;425}426return ret;427}428429MAV_RESULT GCS_MAVLINK_Tracker::handle_command_component_arm_disarm(const mavlink_command_int_t &packet)430{431if (is_equal(packet.param1,1.0f)) {432tracker.arm_servos();433return MAV_RESULT_ACCEPTED;434}435if (is_zero(packet.param1)) {436tracker.disarm_servos();437return MAV_RESULT_ACCEPTED;438}439return MAV_RESULT_UNSUPPORTED;440}441442MAV_RESULT GCS_MAVLINK_Tracker::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)443{444switch(packet.command) {445446case MAV_CMD_DO_SET_SERVO:447// ensure we are in servo test mode448tracker.set_mode(tracker.mode_servotest, ModeReason::SERVOTEST);449450if (!tracker.mode_servotest.set_servo(packet.param1, packet.param2)) {451return MAV_RESULT_FAILED;452}453return MAV_RESULT_ACCEPTED;454455// mavproxy/mavutil sends this when auto command is entered456case MAV_CMD_MISSION_START:457tracker.set_mode(tracker.mode_auto, ModeReason::GCS_COMMAND);458return MAV_RESULT_ACCEPTED;459460default:461return GCS_MAVLINK::handle_command_int_packet(packet, msg);462}463}464465void GCS_MAVLINK_Tracker::handle_message(const mavlink_message_t &msg)466{467switch (msg.msgid) {468469case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:470handle_set_attitude_target(msg);471break;472473#if AP_TRACKER_SET_HOME_VIA_MISSION_UPLOAD_ENABLED474// When mavproxy 'wp sethome'475case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:476handle_message_mission_write_partial_list(msg);477break;478479// XXX receive a WP from GCS and store in EEPROM if it is HOME480case MAVLINK_MSG_ID_MISSION_ITEM:481handle_message_mission_item(msg);482break;483#endif484485case MAVLINK_MSG_ID_MANUAL_CONTROL:486handle_message_manual_control(msg);487break;488489case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:490handle_message_global_position_int(msg);491break;492493case MAVLINK_MSG_ID_SCALED_PRESSURE:494handle_message_scaled_pressure(msg);495break;496}497498GCS_MAVLINK::handle_message(msg);499}500501502#if AP_TRACKER_SET_HOME_VIA_MISSION_UPLOAD_ENABLED503void GCS_MAVLINK_Tracker::handle_message_mission_write_partial_list(const mavlink_message_t &msg)504{505// decode506mavlink_mission_write_partial_list_t packet;507mavlink_msg_mission_write_partial_list_decode(&msg, &packet);508if (packet.start_index == 0)509{510// New home at wp index 0. Ask for it511waypoint_receiving = true;512send_message(MSG_NEXT_MISSION_REQUEST_WAYPOINTS);513}514}515516void GCS_MAVLINK_Tracker::handle_message_mission_item(const mavlink_message_t &msg)517{518mavlink_mission_item_t packet;519MAV_MISSION_RESULT result = MAV_MISSION_ACCEPTED;520521mavlink_msg_mission_item_decode(&msg, &packet);522523Location tell_command;524525switch (packet.frame)526{527case MAV_FRAME_MISSION:528case MAV_FRAME_GLOBAL:529{530tell_command = Location{531int32_t(1.0e7f*packet.x), // in as DD converted to * t7532int32_t(1.0e7f*packet.y), // in as DD converted to * t7533int32_t(packet.z*1.0e2f), // in as m converted to cm534Location::AltFrame::ABSOLUTE535};536break;537}538539#ifdef MAV_FRAME_LOCAL_NED540case MAV_FRAME_LOCAL_NED: // local (relative to home position)541{542tell_command = Location{543int32_t(1.0e7f*ToDeg(packet.x/(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat),544int32_t(1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng),545int32_t(-packet.z*1.0e2f),546Location::AltFrame::ABOVE_HOME547};548break;549}550#endif551552#ifdef MAV_FRAME_LOCAL553case MAV_FRAME_LOCAL: // local (relative to home position)554{555tell_command = {556int32_t(1.0e7f*ToDeg(packet.x/(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat),557int32_t(1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng),558int32_t(packet.z*1.0e2f),559Location::AltFrame::ABOVE_HOME560};561break;562}563#endif564565case MAV_FRAME_GLOBAL_RELATIVE_ALT: // absolute lat/lng, relative altitude566{567tell_command = {568int32_t(1.0e7f * packet.x), // in as DD converted to * t7569int32_t(1.0e7f * packet.y), // in as DD converted to * t7570int32_t(packet.z * 1.0e2f),571Location::AltFrame::ABOVE_HOME572};573break;574}575576default:577result = MAV_MISSION_UNSUPPORTED_FRAME;578break;579}580581if (result != MAV_MISSION_ACCEPTED) goto mission_failed;582583// Check if receiving waypoints (mission upload expected)584if (!waypoint_receiving) {585result = MAV_MISSION_ERROR;586goto mission_failed;587}588589// check if this is the HOME wp590if (packet.seq == 0) {591if (!tracker.set_home(tell_command, false)) {592result = MAV_MISSION_ERROR;593goto mission_failed;594}595send_text(MAV_SEVERITY_INFO,"New HOME received");596waypoint_receiving = false;597}598599mission_failed:600// send ACK (including in success case)601mavlink_msg_mission_ack_send(602chan,603msg.sysid,604msg.compid,605result,606MAV_MISSION_TYPE_MISSION);607}608#endif609610void GCS_MAVLINK_Tracker::handle_message_manual_control(const mavlink_message_t &msg)611{612mavlink_manual_control_t packet;613mavlink_msg_manual_control_decode(&msg, &packet);614tracker.tracking_manual_control(packet);615}616617void GCS_MAVLINK_Tracker::handle_message_global_position_int(const mavlink_message_t &msg)618{619// decode620mavlink_global_position_int_t packet;621mavlink_msg_global_position_int_decode(&msg, &packet);622tracker.tracking_update_position(packet);623}624625void GCS_MAVLINK_Tracker::handle_message_scaled_pressure(const mavlink_message_t &msg)626{627mavlink_scaled_pressure_t packet;628mavlink_msg_scaled_pressure_decode(&msg, &packet);629tracker.tracking_update_pressure(packet);630}631632// send position tracker is using633void GCS_MAVLINK_Tracker::send_global_position_int()634{635if (!tracker.stationary) {636GCS_MAVLINK::send_global_position_int();637return;638}639640mavlink_msg_global_position_int_send(641chan,642AP_HAL::millis(),643tracker.current_loc.lat, // in 1E7 degrees644tracker.current_loc.lng, // in 1E7 degrees645tracker.current_loc.alt, // millimeters above ground/sea level6460, // millimeters above home6470, // X speed cm/s (+ve North)6480, // Y speed cm/s (+ve East)6490, // Z speed cm/s (+ve Down)650tracker.ahrs.yaw_sensor); // compass heading in 1/100 degree651}652653// Send the mode with the given index (not mode number!) return the total number of modes654// Index starts at 1655uint8_t GCS_MAVLINK_Tracker::send_available_mode(uint8_t index) const656{657const Mode* modes[] {658&tracker.mode_manual,659&tracker.mode_stop,660&tracker.mode_scan,661&tracker.mode_guided,662&tracker.mode_servotest,663&tracker.mode_auto,664&tracker.mode_initialising,665};666667const uint8_t mode_count = ARRAY_SIZE(modes);668669// Convert to zero indexed670const uint8_t index_zero = index - 1;671if (index_zero >= mode_count) {672// Mode does not exist!?673return mode_count;674}675676// Ask the mode for its name and number677const char* name = modes[index_zero]->name();678const uint8_t mode_number = (uint8_t)modes[index_zero]->number();679680mavlink_msg_available_modes_send(681chan,682mode_count,683index,684MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,685mode_number,6860, // MAV_MODE_PROPERTY bitmask687name688);689690return mode_count;691}692693694