Path: blob/master/AntennaTracker/GCS_MAVLink_Tracker.cpp
9532 views
#include "GCS_MAVLink_Tracker.h"1#include "Tracker.h"23MAV_TYPE GCS_Tracker::frame_type() const4{5return MAV_TYPE_ANTENNA_TRACKER;6}78uint8_t 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 _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_attitude_target()66{67Quaternion quat;68bool use_yaw_rate = false;69float yaw_rate_rads = 0.0;70bool use_pitch_rate = false;71float pitch_rate_rads = 0.0;72float quat_out[4] {0.0, 0.0, 0.0, 0.0};73uint16_t typemask = ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE |74ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE;7576if (tracker.mode->number() == Mode::Number::GUIDED) {77quat = tracker.mode_guided.get_attitude_target_quat();78use_yaw_rate = tracker.mode_guided.get_attitude_target_use_yaw_rate();79use_pitch_rate = tracker.mode_guided.get_attitude_target_use_pitch_rate();80quat_out[0] = quat.q1;81quat_out[1] = quat.q2;82quat_out[2] = quat.q3;83quat_out[3] = quat.q4;84if (!use_yaw_rate) {85typemask |= ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE;86} else {87yaw_rate_rads = tracker.mode_guided.get_attitude_target_yaw_rate_rads();88}89if (!use_pitch_rate) {90typemask |= ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE;91} else {92pitch_rate_rads = tracker.mode_guided.get_attitude_target_pitch_rate_rads();93}9495} else if (tracker.mode->number() == Mode::Number::AUTO) {96float yaw = tracker.mode_auto.get_auto_target_yaw_deg();97float pitch = tracker.mode_auto.get_auto_target_pitch_deg();98quat.from_euler(0, radians(pitch), radians(yaw));99quat_out[0] = quat.q1;100quat_out[1] = quat.q2;101quat_out[2] = quat.q3;102quat_out[3] = quat.q4;103104typemask |=105ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE |106ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE |107ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE |108ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE;109110} else if (tracker.mode->number() == Mode::Number::SCAN) {111struct Tracker::NavStatus &nav_status = tracker.nav_status;112Parameters &g = tracker.g;113114if (!nav_status.manual_control_yaw) {115yaw_rate_rads = radians(g.scan_speed_yaw);116} else {117typemask |= ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE;118}119120if (!nav_status.manual_control_pitch) {121pitch_rate_rads = radians(g.scan_speed_pitch);122} else {123typemask |= ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE;124}125126typemask |= ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE;127128} else if (tracker.mode->number() == Mode::Number::STOP) {129typemask |= ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE;130131} else {132return;133}134135mavlink_msg_attitude_target_send(136chan,137AP_HAL::millis(), // time since boot (ms)138typemask, // Bitmask that tells the system what control dimensions should be ignored by the vehicle139quat_out, // Attitude quaternion [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], unit-length1400, // roll rate (rad/s)141pitch_rate_rads, // pitch rate (rad/s)142yaw_rate_rads, // yaw rate (rad/s)1430); // Collective thrust144}145146void GCS_MAVLINK_Tracker::send_nav_controller_output() const147{148float alt_diff = (tracker.g.alt_source == ALT_SOURCE_BARO) ? tracker.nav_status.alt_difference_baro : tracker.nav_status.alt_difference_gps;149150mavlink_msg_nav_controller_output_send(151chan,1520,153tracker.nav_status.pitch,154tracker.nav_status.bearing,155tracker.nav_status.bearing,156MIN(tracker.nav_status.distance, UINT16_MAX),157alt_diff,1580,1590);160}161162void GCS_MAVLINK_Tracker::handle_set_attitude_target(const mavlink_message_t &msg)163{164// decode packet165mavlink_set_attitude_target_t packet;166mavlink_msg_set_attitude_target_decode(&msg, &packet);167168// exit if vehicle is not in Guided mode169if (tracker.mode != &tracker.mode_guided) {170return;171}172173// sanity checks:174if (!is_zero(packet.body_roll_rate)) {175return;176}177if (!(packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE)) {178// not told to ignore body roll rate179return;180}181if (!(packet.type_mask & ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE)) {182// not told to ignore throttle183return;184}185if (packet.type_mask & ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE) {186// told to ignore attitude (we don't allow continuous motion yet)187return;188}189if ((packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE) &&190(packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE)) {191// told to ignore both pitch and yaw rates - nothing to do?!192return;193}194195const bool use_yaw_rate = !(packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE);196const bool use_pitch_rate = !(packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE);197198tracker.mode_guided.set_angle(199Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]),200use_yaw_rate,201packet.body_yaw_rate,202use_pitch_rate,203packet.body_pitch_rate);204}205206/*207send PID tuning message208*/209void GCS_MAVLINK_Tracker::send_pid_tuning()210{211const Parameters &g = tracker.g;212213// Pitch PID214if (g.gcs_pid_mask & 1) {215const AP_PIDInfo *pid_info = &g.pidPitch2Srv.get_pid_info();216mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,217pid_info->target,218pid_info->actual,219pid_info->FF,220pid_info->P,221pid_info->I,222pid_info->D,223pid_info->slew_rate,224pid_info->Dmod);225if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {226return;227}228}229230// Yaw PID231if (g.gcs_pid_mask & 2) {232const AP_PIDInfo *pid_info = &g.pidYaw2Srv.get_pid_info();233mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW,234pid_info->target,235pid_info->actual,236pid_info->FF,237pid_info->P,238pid_info->I,239pid_info->D,240pid_info->slew_rate,241pid_info->Dmod);242if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {243return;244}245}246}247248/*249We eavesdrop on MAVLINK_MSG_ID_GLOBAL_POSITION_INT and250MAVLINK_MSG_ID_SCALED_PRESSUREs251*/252void GCS_MAVLINK_Tracker::packetReceived(const mavlink_status_t &status,253const mavlink_message_t &msg)254{255// return immediately if sysid doesn't match our target sysid256if ((tracker.g.sysid_target != 0) && (tracker.g.sysid_target != msg.sysid)) {257GCS_MAVLINK::packetReceived(status, msg);258return;259}260261switch (msg.msgid) {262case MAVLINK_MSG_ID_HEARTBEAT:263{264mavlink_check_target(msg);265break;266}267268case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:269{270// decode271mavlink_global_position_int_t packet;272mavlink_msg_global_position_int_decode(&msg, &packet);273tracker.tracking_update_position(packet);274break;275}276277case MAVLINK_MSG_ID_SCALED_PRESSURE:278{279// decode280mavlink_scaled_pressure_t packet;281mavlink_msg_scaled_pressure_decode(&msg, &packet);282tracker.tracking_update_pressure(packet);283break;284}285}286GCS_MAVLINK::packetReceived(status, msg);287}288289bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)290{291switch(id) {292case MSG_WIND: // other vehicles do something custom with wind:293return true;294default:295return GCS_MAVLINK::try_send_message(id);296}297return true;298}299300// locks onto a particular target sysid and sets it's position data stream to at least 1hz301void GCS_MAVLINK_Tracker::mavlink_check_target(const mavlink_message_t &msg)302{303// exit immediately if the target has already been set304if (tracker.target_set) {305return;306}307308// decode309mavlink_heartbeat_t packet;310mavlink_msg_heartbeat_decode(&msg, &packet);311312// exit immediately if this is not a vehicle we would track313if ((packet.type == MAV_TYPE_ANTENNA_TRACKER) ||314(packet.type == MAV_TYPE_GCS) ||315(packet.type == MAV_TYPE_ONBOARD_CONTROLLER) ||316(packet.type == MAV_TYPE_GIMBAL)) {317return;318}319320// set our sysid to the target, this ensures we lock onto a single vehicle321if (tracker.g.sysid_target == 0) {322tracker.g.sysid_target.set(msg.sysid);323}324325// send data stream request to target on all channels326// Note: this doesn't check success for all sends meaning it's not guaranteed the vehicle's positions will be sent at 1hz327tracker.gcs().request_datastream_position(msg.sysid, msg.compid);328tracker.gcs().request_datastream_airpressure(msg.sysid, msg.compid);329330// flag target has been set331tracker.target_set = true;332}333334MAV_RESULT GCS_MAVLINK_Tracker::_handle_command_preflight_calibration_baro(const mavlink_message_t &msg)335{336MAV_RESULT ret = GCS_MAVLINK::_handle_command_preflight_calibration_baro(msg);337if (ret == MAV_RESULT_ACCEPTED) {338// zero the altitude difference on next baro update339tracker.nav_status.need_altitude_calibration = true;340}341return ret;342}343344MAV_RESULT GCS_MAVLINK_Tracker::handle_command_component_arm_disarm(const mavlink_command_int_t &packet)345{346if (is_equal(packet.param1,1.0f)) {347tracker.arm_servos();348return MAV_RESULT_ACCEPTED;349}350if (is_zero(packet.param1)) {351tracker.disarm_servos();352return MAV_RESULT_ACCEPTED;353}354return MAV_RESULT_UNSUPPORTED;355}356357MAV_RESULT GCS_MAVLINK_Tracker::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)358{359switch(packet.command) {360361case MAV_CMD_DO_SET_SERVO:362// ensure we are in servo test mode363tracker.set_mode(tracker.mode_servotest, ModeReason::SERVOTEST);364365if (!tracker.mode_servotest.set_servo(packet.param1, packet.param2)) {366return MAV_RESULT_FAILED;367}368return MAV_RESULT_ACCEPTED;369370// mavproxy/mavutil sends this when auto command is entered371case MAV_CMD_MISSION_START:372tracker.set_mode(tracker.mode_auto, ModeReason::GCS_COMMAND);373return MAV_RESULT_ACCEPTED;374375default:376return GCS_MAVLINK::handle_command_int_packet(packet, msg);377}378}379380void GCS_MAVLINK_Tracker::handle_message(const mavlink_message_t &msg)381{382switch (msg.msgid) {383384case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:385handle_set_attitude_target(msg);386break;387388#if AP_TRACKER_SET_HOME_VIA_MISSION_UPLOAD_ENABLED389// When mavproxy 'wp sethome'390case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:391handle_message_mission_write_partial_list(msg);392break;393394// XXX receive a WP from GCS and store in EEPROM if it is HOME395case MAVLINK_MSG_ID_MISSION_ITEM:396handle_message_mission_item(msg);397break;398#endif399400case MAVLINK_MSG_ID_MANUAL_CONTROL:401handle_message_manual_control(msg);402break;403404case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:405handle_message_global_position_int(msg);406break;407408case MAVLINK_MSG_ID_SCALED_PRESSURE:409handle_message_scaled_pressure(msg);410break;411}412413GCS_MAVLINK::handle_message(msg);414}415416417#if AP_TRACKER_SET_HOME_VIA_MISSION_UPLOAD_ENABLED418void GCS_MAVLINK_Tracker::handle_message_mission_write_partial_list(const mavlink_message_t &msg)419{420// decode421mavlink_mission_write_partial_list_t packet;422mavlink_msg_mission_write_partial_list_decode(&msg, &packet);423if (packet.start_index == 0)424{425// New home at wp index 0. Ask for it426waypoint_receiving = true;427send_message(MSG_NEXT_MISSION_REQUEST_WAYPOINTS);428}429}430431void GCS_MAVLINK_Tracker::handle_message_mission_item(const mavlink_message_t &msg)432{433mavlink_mission_item_t packet;434MAV_MISSION_RESULT result = MAV_MISSION_ACCEPTED;435436mavlink_msg_mission_item_decode(&msg, &packet);437438Location tell_command;439440switch (packet.frame)441{442case MAV_FRAME_MISSION:443case MAV_FRAME_GLOBAL:444{445tell_command = Location{446int32_t(1.0e7f*packet.x), // in as DD converted to * t7447int32_t(1.0e7f*packet.y), // in as DD converted to * t7448int32_t(packet.z*1.0e2f), // in as m converted to cm449Location::AltFrame::ABSOLUTE450};451break;452}453454#ifdef MAV_FRAME_LOCAL_NED455case MAV_FRAME_LOCAL_NED: // local (relative to home position)456{457tell_command = Location{458int32_t(1.0e7f*degrees(packet.x/(RADIUS_OF_EARTH*cosf(radians(home.lat/1.0e7f)))) + home.lat),459int32_t(1.0e7f*degrees(packet.y/RADIUS_OF_EARTH) + home.lng),460int32_t(-packet.z*1.0e2f),461Location::AltFrame::ABOVE_HOME462};463break;464}465#endif466467#ifdef MAV_FRAME_LOCAL468case MAV_FRAME_LOCAL: // local (relative to home position)469{470tell_command = {471int32_t(1.0e7f*degrees(packet.x/(RADIUS_OF_EARTH*cosf(radians(home.lat/1.0e7f)))) + home.lat),472int32_t(1.0e7f*degrees(packet.y/RADIUS_OF_EARTH) + home.lng),473int32_t(packet.z*1.0e2f),474Location::AltFrame::ABOVE_HOME475};476break;477}478#endif479480case MAV_FRAME_GLOBAL_RELATIVE_ALT: // absolute lat/lng, relative altitude481{482tell_command = {483int32_t(1.0e7f * packet.x), // in as DD converted to * t7484int32_t(1.0e7f * packet.y), // in as DD converted to * t7485int32_t(packet.z * 1.0e2f),486Location::AltFrame::ABOVE_HOME487};488break;489}490491default:492result = MAV_MISSION_UNSUPPORTED_FRAME;493break;494}495496if (result != MAV_MISSION_ACCEPTED) goto mission_failed;497498// Check if receiving waypoints (mission upload expected)499if (!waypoint_receiving) {500result = MAV_MISSION_ERROR;501goto mission_failed;502}503504// check if this is the HOME wp505if (packet.seq == 0) {506if (!tracker.set_home(tell_command, false)) {507result = MAV_MISSION_ERROR;508goto mission_failed;509}510send_text(MAV_SEVERITY_INFO,"New HOME received");511waypoint_receiving = false;512}513514mission_failed:515// send ACK (including in success case)516mavlink_msg_mission_ack_send(517chan,518msg.sysid,519msg.compid,520result,521MAV_MISSION_TYPE_MISSION);522}523#endif524525void GCS_MAVLINK_Tracker::handle_message_manual_control(const mavlink_message_t &msg)526{527mavlink_manual_control_t packet;528mavlink_msg_manual_control_decode(&msg, &packet);529tracker.tracking_manual_control(packet);530}531532void GCS_MAVLINK_Tracker::handle_message_global_position_int(const mavlink_message_t &msg)533{534// decode535mavlink_global_position_int_t packet;536mavlink_msg_global_position_int_decode(&msg, &packet);537tracker.tracking_update_position(packet);538}539540void GCS_MAVLINK_Tracker::handle_message_scaled_pressure(const mavlink_message_t &msg)541{542mavlink_scaled_pressure_t packet;543mavlink_msg_scaled_pressure_decode(&msg, &packet);544tracker.tracking_update_pressure(packet);545}546547// send position tracker is using548void GCS_MAVLINK_Tracker::send_global_position_int()549{550if (!tracker.stationary) {551GCS_MAVLINK::send_global_position_int();552return;553}554555mavlink_msg_global_position_int_send(556chan,557AP_HAL::millis(),558tracker.current_loc.lat, // in 1E7 degrees559tracker.current_loc.lng, // in 1E7 degrees560tracker.current_loc.alt, // millimeters above ground/sea level5610, // millimeters above home5620, // X speed cm/s (+ve North)5630, // Y speed cm/s (+ve East)5640, // Z speed cm/s (+ve Down)565tracker.ahrs.yaw_sensor); // compass heading in 1/100 degree566}567568// Send the mode with the given index (not mode number!) return the total number of modes569// Index starts at 1570uint8_t GCS_MAVLINK_Tracker::send_available_mode(uint8_t index) const571{572const Mode* modes[] {573&tracker.mode_manual,574&tracker.mode_stop,575&tracker.mode_scan,576&tracker.mode_guided,577&tracker.mode_servotest,578&tracker.mode_auto,579&tracker.mode_initialising,580};581582const uint8_t mode_count = ARRAY_SIZE(modes);583584// Convert to zero indexed585const uint8_t index_zero = index - 1;586if (index_zero >= mode_count) {587// Mode does not exist!?588return mode_count;589}590591// Ask the mode for its name and number592const char* name = modes[index_zero]->name();593const uint8_t mode_number = (uint8_t)modes[index_zero]->number();594595mavlink_msg_available_modes_send(596chan,597mode_count,598index,599MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,600mode_number,6010, // MAV_MODE_PROPERTY bitmask602name603);604605return mode_count;606}607608609