/*===================================================================== PIXHAWK Micro Air Vehicle Flying Robotics Toolkit (c) 2009, 2010 PIXHAWK PROJECT This file is part of the PIXHAWK project PIXHAWK is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. PIXHAWK is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with PIXHAWK. If not, see . ======================================================================*/ /** * @file * @brief Represents one unmanned aerial vehicle * * @author Lorenz Meier * */ #include #include #include #include #include #include #include "UAS.h" #include "LinkInterface.h" #include "UASManager.h" #include "MG.h" #include "QGC.h" #include "GAudioOutput.h" #include "MAVLinkProtocol.h" #include UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), uasId(id), startTime(MG::TIME::getGroundTimeNow()), commStatus(COMM_DISCONNECTED), name(""), links(new QList()), unknownPackets(), mavlink(protocol), waypointManager(*this), thrustSum(0), thrustMax(10), startVoltage(0), currentVoltage(12.0f), lpVoltage(12.0f), mode(MAV_MODE_UNINIT), status(MAV_STATE_UNINIT), onboardTimeOffset(0), controlRollManual(true), controlPitchManual(true), controlYawManual(true), controlThrustManual(true), manualRollAngle(0), manualPitchAngle(0), manualYawAngle(0), manualThrust(0), receiveDropRate(0), sendDropRate(0), lowBattAlarm(false), positionLock(false), statusTimeout(new QTimer(this)) { color = UASInterface::getNextColor(); setBattery(LIPOLY, 3); statusTimeout->setInterval(500); connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState())); } UAS::~UAS() { delete links; } int UAS::getUASID() const { return uasId; } void UAS::updateState() { // Position lock is set by the MAVLink message handler // if no position lock is available, indicate an error if (positionLock) { positionLock = false; } else { if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock) { GAudioOutput::instance()->notifyNegative(); } } } void UAS::setSelected() { UASManager::instance()->setActiveUAS(this); } void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) { if (!links->contains(link)) { addLink(link); // qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName(); } // else // { // qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST"; // } // qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq; if (message.sysid == uasId) { QString uasState; QString stateDescription; QString patternPath; switch (message.msgid) { case MAVLINK_MSG_ID_HEARTBEAT: emit heartbeat(this); // Set new type if it has changed if (this->type != mavlink_msg_heartbeat_get_type(&message)) { this->type = mavlink_msg_heartbeat_get_type(&message); emit systemTypeSet(this, type); } break; case MAVLINK_MSG_ID_BOOT: getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription); emit statusChanged(this, uasState, stateDescription); onboardTimeOffset = 0; // Reset offset measurement break; case MAVLINK_MSG_ID_SYS_STATUS: { mavlink_sys_status_t state; mavlink_msg_sys_status_decode(&message, &state); // FIXME //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode; QString audiostring = "System " + QString::number(this->getUASID()); QString stateAudio = ""; QString modeAudio = ""; bool statechanged = false; bool modechanged = false; if (state.status != this->status) { statechanged = true; this->status = (int)state.status; getStatusForCode((int)state.status, uasState, stateDescription); emit statusChanged(this, uasState, stateDescription); emit statusChanged(this->status); stateAudio = " changed status to " + uasState; } if (this->mode != static_cast(state.mode)) { modechanged = true; this->mode = static_cast(state.mode); QString mode; switch (state.mode) { case (uint8_t)MAV_MODE_LOCKED: mode = "LOCKED MODE"; break; case (uint8_t)MAV_MODE_MANUAL: mode = "MANUAL MODE"; break; case (uint8_t)MAV_MODE_AUTO: mode = "AUTO MODE"; break; case (uint8_t)MAV_MODE_GUIDED: mode = "GUIDED MODE"; break; case (uint8_t)MAV_MODE_READY: mode = "READY"; break; case (uint8_t)MAV_MODE_TEST1: mode = "TEST1 MODE"; break; case (uint8_t)MAV_MODE_TEST2: mode = "TEST2 MODE"; break; case (uint8_t)MAV_MODE_TEST3: mode = "TEST3 MODE"; break; default: mode = "UNINIT MODE"; break; } emit modeChanged(this->getUASID(), mode, ""); modeAudio = " is now in " + mode; } currentVoltage = state.vbat/1000.0f; lpVoltage = filterVoltage(currentVoltage); if (startVoltage == 0) startVoltage = currentVoltage; timeRemaining = calculateTimeRemaining(); //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining; emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining); emit voltageChanged(message.sysid, state.vbat/1000.0f); // LOW BATTERY ALARM float chargeLevel = getChargeLevel(); if (chargeLevel <= 10.0f) { startLowBattAlarm(); } else { stopLowBattAlarm(); } // COMMUNICATIONS DROP RATE emit dropRateChanged(this->getUASID(), state.packet_drop); //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop; // AUDIO if (modechanged && statechanged) { // Output both messages audiostring += modeAudio + " and " + stateAudio; } else { // Output the one message audiostring += modeAudio + stateAudio; } if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY) { GAudioOutput::instance()->startEmergency(); } else if (modechanged || statechanged) { GAudioOutput::instance()->stopEmergency(); GAudioOutput::instance()->say(audiostring); } } break; case MAVLINK_MSG_ID_RAW_IMU: { mavlink_raw_imu_t raw; mavlink_msg_raw_imu_decode(&message, &raw); quint64 time = getUnixTime(raw.usec); emit valueChanged(uasId, "Accel. X", raw.xacc, time); emit valueChanged(uasId, "Accel. Y", raw.yacc, time); emit valueChanged(uasId, "Accel. Z", raw.zacc, time); emit valueChanged(uasId, "Gyro Phi", raw.xgyro, time); emit valueChanged(uasId, "Gyro Theta", raw.ygyro, time); emit valueChanged(uasId, "Gyro Psi", raw.zgyro, time); emit valueChanged(uasId, "Mag. X", raw.xmag, time); emit valueChanged(uasId, "Mag. Y", raw.ymag, time); emit valueChanged(uasId, "Mag. Z", raw.zmag, time); } break; case MAVLINK_MSG_ID_ATTITUDE: //std::cerr << std::endl; //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl; { mavlink_attitude_t attitude; mavlink_msg_attitude_decode(&message, &attitude); quint64 time = getUnixTime(attitude.usec); emit valueChanged(uasId, "roll IMU", mavlink_msg_attitude_get_roll(&message), time); emit valueChanged(uasId, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time); emit valueChanged(uasId, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time); emit valueChanged(this, "roll IMU", mavlink_msg_attitude_get_roll(&message), time); emit valueChanged(this, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time); emit valueChanged(this, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time); emit valueChanged(uasId, "rollspeed IMU", attitude.rollspeed, time); emit valueChanged(uasId, "pitchspeed IMU", attitude.pitchspeed, time); emit valueChanged(uasId, "yawspeed IMU", attitude.yawspeed, time); emit attitudeChanged(this, mavlink_msg_attitude_get_roll(&message), mavlink_msg_attitude_get_pitch(&message), mavlink_msg_attitude_get_yaw(&message), time); } break; case MAVLINK_MSG_ID_LOCAL_POSITION: //std::cerr << std::endl; //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl; { mavlink_local_position_t pos; mavlink_msg_local_position_decode(&message, &pos); quint64 time = getUnixTime(pos.usec); emit valueChanged(uasId, "x", pos.x, time); emit valueChanged(uasId, "y", pos.y, time); emit valueChanged(uasId, "z", pos.z, time); emit valueChanged(uasId, "Vx", pos.vx, time); emit valueChanged(uasId, "Vy", pos.vy, time); emit valueChanged(uasId, "Vz", pos.vz, time); emit localPositionChanged(this, pos.x, pos.y, pos.z, time); emit speedChanged(this, pos.vx, pos.vy, pos.vz, time); //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time); // Set internal state if (!positionLock) { // If position was not locked before, notify positive GAudioOutput::instance()->notifyPositive(); } positionLock = true; } break; case MAVLINK_MSG_ID_GLOBAL_POSITION: //std::cerr << std::endl; //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl; { mavlink_global_position_t pos; mavlink_msg_global_position_decode(&message, &pos); quint64 time = getUnixTime(pos.usec); emit valueChanged(uasId, "lat", pos.lat, time); emit valueChanged(uasId, "lon", pos.lon, time); emit valueChanged(uasId, "alt", pos.alt, time); emit valueChanged(uasId, "g-vx", pos.vx, time); emit valueChanged(uasId, "g-vy", pos.vy, time); emit valueChanged(uasId, "g-vz", pos.vz, time); emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time); emit speedChanged(this, pos.vx, pos.vy, pos.vz, time); // Set internal state if (!positionLock) { // If position was not locked before, notify positive GAudioOutput::instance()->notifyPositive(); } positionLock = true; } break; case MAVLINK_MSG_ID_GPS_RAW: //std::cerr << std::endl; //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl; { mavlink_gps_raw_t pos; mavlink_msg_gps_raw_decode(&message, &pos); // SANITY CHECK // only accept values in a realistic range // quint64 time = getUnixTime(pos.usec); quint64 time = MG::TIME::getGroundTimeNow(); emit valueChanged(uasId, "lat", pos.lat, time); emit valueChanged(uasId, "lon", pos.lon, time); // Check for NaN int alt = pos.alt; if (alt != alt) { alt = 0; emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE"); } emit valueChanged(uasId, "alt", pos.alt, time); // Smaller than threshold and not NaN if (pos.v < 1000000 && pos.v == pos.v) { emit valueChanged(uasId, "speed", pos.v, time); //qDebug() << "GOT GPS RAW"; emit speedChanged(this, (double)pos.v, 0.0, 0.0, time); } else { emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v)); } emit globalPositionChanged(this, pos.lon, pos.lat, alt, time); } break; case MAVLINK_MSG_ID_GPS_STATUS: { mavlink_gps_status_t pos; mavlink_msg_gps_status_decode(&message, &pos); for(int i = 0; i < (int)pos.satellites_visible; i++) { emit gpsSatelliteStatusChanged(uasId, (unsigned char)pos.satellite_prn[i], (unsigned char)pos.satellite_elevation[i], (unsigned char)pos.satellite_azimuth[i], (unsigned char)pos.satellite_snr[i], static_cast(pos.satellite_used[i])); } } break; case MAVLINK_MSG_ID_PARAM_VALUE: { mavlink_param_value_t value; mavlink_msg_param_value_decode(&message, &value); emit parameterChanged(uasId, message.compid, QString((char*)value.param_id), value.param_value); } break; case MAVLINK_MSG_ID_DEBUG: emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow()); break; case MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT: { mavlink_attitude_controller_output_t out; mavlink_msg_attitude_controller_output_decode(&message, &out); quint64 time = MG::TIME::getGroundTimeNowUsecs(); emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time); emit valueChanged(uasId, "att control roll", out.roll, time/1000.0f); emit valueChanged(uasId, "att control pitch", out.pitch, time/1000.0f); emit valueChanged(uasId, "att control yaw", out.yaw, time/1000.0f); } break; case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT: { mavlink_position_controller_output_t out; mavlink_msg_position_controller_output_decode(&message, &out); quint64 time = MG::TIME::getGroundTimeNow(); //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time); emit valueChanged(uasId, "pos control x", out.x, time); emit valueChanged(uasId, "pos control y", out.y, time); emit valueChanged(uasId, "pos control z", out.z, time); } break; case MAVLINK_MSG_ID_WAYPOINT_COUNT: { mavlink_waypoint_count_t wpc; mavlink_msg_waypoint_count_decode(&message, &wpc); if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId()) { waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count); } } break; case MAVLINK_MSG_ID_WAYPOINT: { mavlink_waypoint_t wp; mavlink_msg_waypoint_decode(&message, &wp); //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z; if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId()) { waypointManager.handleWaypoint(message.sysid, message.compid, &wp); } } break; case MAVLINK_MSG_ID_WAYPOINT_ACK: { mavlink_waypoint_ack_t wpa; mavlink_msg_waypoint_ack_decode(&message, &wpa); if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId()) { waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa); } } break; case MAVLINK_MSG_ID_WAYPOINT_REQUEST: { mavlink_waypoint_request_t wpr; mavlink_msg_waypoint_request_decode(&message, &wpr); if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId()) { waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr); } } break; case MAVLINK_MSG_ID_WAYPOINT_REACHED: { mavlink_waypoint_reached_t wpr; mavlink_msg_waypoint_reached_decode(&message, &wpr); waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr); } break; case MAVLINK_MSG_ID_WAYPOINT_CURRENT: { mavlink_waypoint_current_t wpc; mavlink_msg_waypoint_current_decode(&message, &wpc); waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc); } break; case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT: { mavlink_local_position_setpoint_t p; mavlink_msg_local_position_setpoint_decode(&message, &p); emit positionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw, QGC::groundTimeUsecs()); } break; case MAVLINK_MSG_ID_STATUSTEXT: { QByteArray b; b.resize(256); mavlink_msg_statustext_get_text(&message, (int8_t*)b.data()); //b.append('\0'); QString text = QString(b); int severity = mavlink_msg_statustext_get_severity(&message); //qDebug() << "RECEIVED STATUS:" << text;false //emit statusTextReceived(severity, text); emit textMessageReceived(uasId, message.compid, severity, text); } break; default: { if (!unknownPackets.contains(message.msgid)) { unknownPackets.append(message.msgid); //GAudioOutput::instance()->say("UNABLE TO DECODE MESSAGE WITH ID " + QString::number(message.msgid) + " FROM SYSTEM " + QString::number(message.sysid)); std::cout << "Unable to decode message from system " << std::dec << static_cast(message.sysid) << " with message id:" << static_cast(message.msgid) << std::endl; //qDebug() << std::cerr << "Unable to decode message from system " << std::dec << static_cast(message.acid) << " with message id:" << static_cast(message.msgid) << std::endl; } } break; } } } void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw) { #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES mavlink_message_t msg; mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw); sendMessage(msg); #endif } quint64 UAS::getUnixTime(quint64 time) { if (time == 0) { return MG::TIME::getGroundTimeNow(); } // Check if time is smaller than 40 years, // assuming no system without Unix timestamp // runs longer than 40 years continuously without // reboot. In worst case this will add/subtract the // communication delay between GCS and MAV, // it will never alter the timestamp in a safety // critical way. // // Calculation: // 40 years // 365 days // 24 hours // 60 minutes // 60 seconds // 1000 milliseconds // 1000 microseconds else if (time < 1261440000000000LLU) { if (onboardTimeOffset == 0) { onboardTimeOffset = MG::TIME::getGroundTimeNow() - time/1000; } return time/1000 + onboardTimeOffset; } else { // Time is not zero and larger than 40 years -> has to be // a Unix epoch timestamp. Do nothing. return time/1000; } } void UAS::setMode(int mode) { if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_TEST3) { mavlink_message_t msg; mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode); sendMessage(msg); qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode; } } void UAS::sendMessage(mavlink_message_t message) { // Emit message on all links that are currently connected QList::iterator i; for (i = links->begin(); i != links->end(); ++i) { sendMessage(*i, message); } } void UAS::sendMessage(LinkInterface* link, mavlink_message_t message) { // Create buffer uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; // Write message into buffer, prepending start sign int len = mavlink_msg_to_send_buffer(buffer, &message); // If link is connected if (link->isConnected()) { // Send the portion of the buffer now occupied by the message link->writeBytes((const char*)buffer, len); } } /** * @param value battery voltage */ float UAS::filterVoltage(float value) const { return lpVoltage * 0.7f + value * 0.3f; } void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription) { switch (statusCode) { case MAV_STATE_UNINIT: uasState = tr("UNINIT"); stateDescription = tr("Not initialized"); break; case MAV_STATE_BOOT: uasState = tr("BOOT"); stateDescription = tr("Booting system, please wait.."); break; case MAV_STATE_CALIBRATING: uasState = tr("CALIBRATING"); stateDescription = tr("Calibrating sensors.."); break; case MAV_STATE_ACTIVE: uasState = tr("ACTIVE"); stateDescription = tr("Normal operation mode"); break; case MAV_STATE_STANDBY: uasState = tr("STANDBY"); stateDescription = tr("Standby, operational"); break; case MAV_STATE_CRITICAL: uasState = tr("CRITICAL"); stateDescription = tr("Failure occured!"); break; case MAV_STATE_EMERGENCY: uasState = tr("EMERGENCY"); stateDescription = tr("EMERGENCY: Please land"); break; case MAV_STATE_POWEROFF: uasState = tr("SHUTDOWN"); stateDescription = tr("Powering off system"); break; default: uasState = tr("UNKNOWN"); stateDescription = tr("FAILURE: Unknown system state"); break; } } /* MANAGEMENT */ /* * * @return The uptime in milliseconds * **/ quint64 UAS::getUptime() const { if(startTime == 0) { return 0; } else { return MG::TIME::getGroundTimeNow() - startTime; } } int UAS::getCommunicationStatus() const { return commStatus; } void UAS::requestParameters() { mavlink_message_t msg; mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25); // Send message twice to increase chance of reception sendMessage(msg); } void UAS::writeParametersToStorage() { mavlink_message_t msg; // TODO Replace MG System ID with static function call and allow to change ID in GUI mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_STORAGE_WRITE); //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE); sendMessage(msg); } void UAS::readParametersFromStorage() { mavlink_message_t msg; // TODO Replace MG System ID with static function call and allow to change ID in GUI mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(uint8_t)MAV_ACTION_STORAGE_READ); sendMessage(msg); } void UAS::enableAllDataTransmission(bool enabled) { #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; // Select the message to request from now on // 0 is a magic ID and will enable/disable the standard message set except for heartbeat stream.req_stream_id = 0; // Select the update rate in Hz the message should be send // All messages will be send with their default rate stream.req_message_rate = 0; // Start / stop the message stream.start_stop = (enabled) ? 1 : 0; // The system which should take this command stream.target_system = uasId; // The component / subsystem which should take this command stream.target_component = 0; // Encode and send the message mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); #endif } void UAS::enableRawSensorDataTransmission(bool enabled) { #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; // Select the message to request from now on stream.req_stream_id = 1; // Select the update rate in Hz the message should be send stream.req_message_rate = 200; // Start / stop the message stream.start_stop = (enabled) ? 1 : 0; // The system which should take this command stream.target_system = uasId; // The component / subsystem which should take this command stream.target_component = 0; // Encode and send the message mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); #endif } void UAS::enableExtendedSystemStatusTransmission(bool enabled) { #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; // Select the message to request from now on stream.req_stream_id = 2; // Select the update rate in Hz the message should be send stream.req_message_rate = 10; // Start / stop the message stream.start_stop = (enabled) ? 1 : 0; // The system which should take this command stream.target_system = uasId; // The component / subsystem which should take this command stream.target_component = 0; // Encode and send the message mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); #endif } void UAS::enableRCChannelDataTransmission(bool enabled) { #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; // Select the message to request from now on stream.req_stream_id = 3; // Select the update rate in Hz the message should be send stream.req_message_rate = 200; // Start / stop the message stream.start_stop = (enabled) ? 1 : 0; // The system which should take this command stream.target_system = uasId; // The component / subsystem which should take this command stream.target_component = 0; // Encode and send the message mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); #endif } void UAS::enableRawControllerDataTransmission(bool enabled) { #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; // Select the message to request from now on stream.req_stream_id = 4; // Select the update rate in Hz the message should be send stream.req_message_rate = 200; // Start / stop the message stream.start_stop = (enabled) ? 1 : 0; // The system which should take this command stream.target_system = uasId; // The component / subsystem which should take this command stream.target_component = 0; // Encode and send the message mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); #endif } void UAS::enableRawSensorFusionTransmission(bool enabled) { #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; // Select the message to request from now on stream.req_stream_id = 5; // Select the update rate in Hz the message should be send stream.req_message_rate = 200; // Start / stop the message stream.start_stop = (enabled) ? 1 : 0; // The system which should take this command stream.target_system = uasId; // The component / subsystem which should take this command stream.target_component = 0; // Encode and send the message mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); #endif } void UAS::enablePositionTransmission(bool enabled) { #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; // Select the message to request from now on stream.req_stream_id = 6; // Select the update rate in Hz the message should be send stream.req_message_rate = 200; // Start / stop the message stream.start_stop = (enabled) ? 1 : 0; // The system which should take this command stream.target_system = uasId; // The component / subsystem which should take this command stream.target_component = 0; // Encode and send the message mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); #endif } void UAS::enableExtra1Transmission(bool enabled) { #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; // Select the message to request from now on stream.req_stream_id = 7; // Select the update rate in Hz the message should be send stream.req_message_rate = 200; // Start / stop the message stream.start_stop = (enabled) ? 1 : 0; // The system which should take this command stream.target_system = uasId; // The component / subsystem which should take this command stream.target_component = 0; // Encode and send the message mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); #endif } void UAS::enableExtra2Transmission(bool enabled) { #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; // Select the message to request from now on stream.req_stream_id = 8; // Select the update rate in Hz the message should be send stream.req_message_rate = 200; // Start / stop the message stream.start_stop = (enabled) ? 1 : 0; // The system which should take this command stream.target_system = uasId; // The component / subsystem which should take this command stream.target_component = 0; // Encode and send the message mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); #endif } void UAS::enableExtra3Transmission(bool enabled) { #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; // Select the message to request from now on stream.req_stream_id = 9; // Select the update rate in Hz the message should be send stream.req_message_rate = 200; // Start / stop the message stream.start_stop = (enabled) ? 1 : 0; // The system which should take this command stream.target_system = uasId; // The component / subsystem which should take this command stream.target_component = 0; // Encode and send the message mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); #endif } void UAS::setParameter(int component, QString id, float value) { mavlink_message_t msg; mavlink_param_set_t p; p.param_value = value; p.target_system = (uint8_t)uasId; p.target_component = (uint8_t)component; // Copy string into buffer, ensuring not to exceed the buffer size for (unsigned int i = 0; i < sizeof(p.param_id); i++) { // String characters if ((int)i < id.length() && i < (sizeof(p.param_id) - 1)) { p.param_id[i] = id.toAscii()[i]; } // Null termination at end of string or end of buffer else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1)) { p.param_id[i] = '\0'; } // Zero fill else { p.param_id[i] = 0; } } mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p); sendMessage(msg); } /** * @brief Launches the system * **/ void UAS::launch() { mavlink_message_t msg; // TODO Replace MG System ID with static function call and allow to change ID in GUI mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_LAUNCH); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); } /** * Depending on the UAS, this might make the rotors of a helicopter spinning * **/ void UAS::enable_motors() { mavlink_message_t msg; // TODO Replace MG System ID with static function call and allow to change ID in GUI mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_START); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); } /** * @warning Depending on the UAS, this might completely stop all motors. * **/ void UAS::disable_motors() { mavlink_message_t msg; // TODO Replace MG System ID with static function call and allow to change ID in GUI mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_MOTORS_STOP); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); } void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust) { // Scale values double rollPitchScaling = 0.2f; double yawScaling = 0.5f; double thrustScaling = 1.0f; manualRollAngle = roll * rollPitchScaling; manualPitchAngle = pitch * rollPitchScaling; manualYawAngle = yaw * yawScaling; manualThrust = thrust * thrustScaling; if(mode == (int)MAV_MODE_MANUAL) { #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES mavlink_message_t message; mavlink_msg_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual); sendMessage(message); qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust; emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow()); #endif } } int UAS::getSystemType() { return this->type; } void UAS::receiveButton(int buttonIndex) { switch (buttonIndex) { case 0: break; case 1: break; default: break; } qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!"; } /*void UAS::requestWaypoints() { // mavlink_message_t msg; // mavlink_msg_waypoint_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 25); // // Send message twice to increase chance of reception // sendMessage(msg); waypointManager.requestWaypoints(); qDebug() << "UAS Request WPs"; } void UAS::setWaypoint(Waypoint* wp) { // mavlink_message_t msg; // mavlink_waypoint_set_t set; // set.id = wp->id; // //QString name = wp->name; // // FIXME Check if this works properly // //name.truncate(MAVLINK_MSG_WAYPOINT_SET_FIELD_NAME_LEN); // //strcpy((char*)set.name, name.toStdString().c_str()); // set.autocontinue = wp->autocontinue; // set.target_component = 25; // FIXME // set.target_system = uasId; // set.active = wp->current; // set.x = wp->x; // set.y = wp->y; // set.z = wp->z; // set.yaw = wp->yaw; // mavlink_msg_waypoint_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &set); // // Send message twice to increase chance of reception // sendMessage(msg); } void UAS::setWaypointActive(int id) { // mavlink_message_t msg; // mavlink_waypoint_set_active_t active; // active.id = id; // active.target_system = uasId; // active.target_component = 25; // FIXME // mavlink_msg_waypoint_set_active_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &active); // // Send message twice to increase chance of reception // sendMessage(msg); // sendMessage(msg); // // TODO This should be not directly emitted, but rather being fed back from the UAS // emit waypointSelected(getUASID(), id); } void UAS::clearWaypointList() { // mavlink_message_t msg; // // FIXME // mavlink_waypoint_clear_list_t clist; // clist.target_system = uasId; // clist.target_component = 25; // FIXME // mavlink_msg_waypoint_clear_list_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &clist); // sendMessage(msg); // qDebug() << "UAS clears Waypoints!"; }*/ void UAS::halt() { mavlink_message_t msg; // TODO Replace MG System ID with static function call and allow to change ID in GUI mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); } void UAS::go() { mavlink_message_t msg; // TODO Replace MG System ID with static function call and allow to change ID in GUI mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_CONTINUE); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); } /** Order the robot to return home / to land on the runway **/ void UAS::home() { mavlink_message_t msg; // TODO Replace MG System ID with static function call and allow to change ID in GUI mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_RETURN); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); } /** * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation * and might differ between systems. */ void UAS::emergencySTOP() { mavlink_message_t msg; // TODO Replace MG System ID with static function call and allow to change ID in GUI mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); } /** * All systems are immediately shut down (e.g. the main power line is cut). * @warning This might lead to a crash * * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards */ bool UAS::emergencyKILL() { bool result = false; QMessageBox msgBox; msgBox.setIcon(QMessageBox::Critical); msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS"); msgBox.setInformativeText("Do you want to cut power on all systems?"); msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel); msgBox.setDefaultButton(QMessageBox::Cancel); int ret = msgBox.exec(); // Close the message box shortly after the click to prevent accidental clicks QTimer::singleShot(5000, &msgBox, SLOT(reject())); if (ret == QMessageBox::Yes) { mavlink_message_t msg; // TODO Replace MG System ID with static function call and allow to change ID in GUI mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); result = true; } return result; } void UAS::shutdown() { bool result = false; QMessageBox msgBox; msgBox.setIcon(QMessageBox::Critical); msgBox.setText("Shutting down the UAS"); msgBox.setInformativeText("Do you want to shut down the onboard computer?"); msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel); msgBox.setDefaultButton(QMessageBox::Cancel); int ret = msgBox.exec(); // Close the message box shortly after the click to prevent accidental clicks QTimer::singleShot(5000, &msgBox, SLOT(reject())); if (ret == QMessageBox::Yes) { // If the active UAS is set, execute command mavlink_message_t msg; // TODO Replace MG System ID with static function call and allow to change ID in GUI mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); result = true; } } /** * @return The name of this system as string in human-readable form */ QString UAS::getUASName(void) const { QString result; if (name == "") { result = tr("MAV ") + result.sprintf("%03d", getUASID()); } else { result = name; } return result; } void UAS::addLink(LinkInterface* link) { if (!links->contains(link)) { links->append(link); } //links->append(link); //qDebug() << " ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK"; } /** * @brief Get the links associated with this robot * **/ QList* UAS::getLinks() { return links; } void UAS::setBattery(BatteryType type, int cells) { this->batteryType = type; this->cells = cells; switch (batteryType) { case NICD: break; case NIMH: break; case LIION: break; case LIPOLY: fullVoltage = this->cells * UAS::lipoFull; emptyVoltage = this->cells * UAS::lipoEmpty; break; case LIFE: break; case AGZN: break; } } int UAS::calculateTimeRemaining() { quint64 dt = MG::TIME::getGroundTimeNow() - startTime; double seconds = dt / 1000.0f; double voltDifference = startVoltage - currentVoltage; if (voltDifference <= 0) voltDifference = 0.00000000001f; double dischargePerSecond = voltDifference / seconds; int remaining = static_cast((currentVoltage - emptyVoltage) / dischargePerSecond); // Can never be below 0 if (remaining < 0) remaining = 0; return remaining; } /** * @return charge level in percent - 0 - 100 */ double UAS::getChargeLevel() { float chargeLevel; if (lpVoltage < emptyVoltage) { chargeLevel = 0.0f; } else if (lpVoltage > fullVoltage) { chargeLevel = 100.0f; } else { chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage)); } return chargeLevel; } void UAS::startLowBattAlarm() { if (!lowBattAlarm) { GAudioOutput::instance()->alert("LOW BATTERY"); QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency())); lowBattAlarm = true; } } void UAS::stopLowBattAlarm() { if (lowBattAlarm) { GAudioOutput::instance()->stopEmergency(); lowBattAlarm = false; } }