diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 9c1390adde19cbfc4ef1ac184f09400681cd713e..0c43dbd6e07039c4f96c598fc85b42f50f3c8600 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -390,14 +390,14 @@ void MAVLinkProtocol::sendHeartbeat() mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, OCU, MAV_AUTOPILOT_GENERIC); sendMessage(beat); } - //if (m_authEnabled) { - //mavlink_message_t msg; - //mavlink_auth_key_t auth; - //if (m_authKey.length() != MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN) m_authKey.resize(MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN); - //strcpy(auth.key, m_authKey.toStdString().c_str()); - //mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth); - //sendMessage(msg); - //} + if (m_authEnabled) { + mavlink_message_t msg; + mavlink_auth_key_t auth; + if (m_authKey.length() != MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN) m_authKey.resize(MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN); + strcpy(auth.key, m_authKey.toStdString().c_str()); + mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth); + sendMessage(msg); + } } /** @param enabled true to enable heartbeats emission at heartbeatRate, false to disable */ diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index bffdddcaec4e161fb428f7bf907ee52ec95d97ec..9efe0f309b19ac0ff66fe809053dc993f7885d95 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -173,7 +173,7 @@ void SerialLink::readBytes() const qint64 maxLength = 2048; char data[maxLength]; qint64 numBytes = port->bytesAvailable(); - //qDebug() << "numBytes: " << numBytes; + //qDebug() << "numBytes: " << numBytes; if(numBytes > 0) { /* Read as much data in buffer as possible without overflow */ diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 20423372b40e5af2a2c11a944c5bbcb96888f7e0..a77f6aec582c2009e1e6358bc12a02742b6db742 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -690,15 +690,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) } break; - //case MAVLINK_MSG_ID_SCALED_PRESSURE: { - //mavlink_scaled_pressure_t pressure; - //mavlink_msg_scaled_pressure_decode(&message, &pressure); - //quint64 time = this->getUnixTime(pressure.usec); - //emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time); - //emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time); - //emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time); - //} - //break; + case MAVLINK_MSG_ID_SCALED_PRESSURE: { + mavlink_scaled_pressure_t pressure; + mavlink_msg_scaled_pressure_decode(&message, &pressure); + quint64 time = this->getUnixTime(pressure.usec); + emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time); + emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time); + emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time); + } + break; case MAVLINK_MSG_ID_RC_CHANNELS_RAW: { mavlink_rc_channels_raw_t channels; @@ -1304,7 +1304,7 @@ void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDesc uasState = tr("EMERGENCY"); stateDescription = tr("EMERGENCY: Land Immediately!"); break; - //case MAV_STATE_HILSIM: + //case MAV_STATE_HILSIM: //uasState = tr("HIL SIM"); //stateDescription = tr("HIL Simulation, Sensors read from SIM"); //break; @@ -1975,24 +1975,24 @@ bool UAS::emergencyKILL() void UAS::startHil() { - //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_START_HILSIM); - //// Send message twice to increase chance of reception - //sendMessage(msg); - //sendMessage(msg); + 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_START_HILSIM); + // Send message twice to increase chance of reception + sendMessage(msg); + sendMessage(msg); } void UAS::stopHil() { - //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_STOP_HILSIM); - //// Send message twice to increase chance of reception - //sendMessage(msg); - //sendMessage(msg); + 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_STOP_HILSIM); + // Send message twice to increase chance of reception + sendMessage(msg); + sendMessage(msg); }