Commit 0d2f136a authored by lm's avatar lm

Merge branch 'dev' of github.com:pixhawk/qgroundcontrol into opmapcontrol

parents 52b20293 a7383a1a
...@@ -390,14 +390,14 @@ void MAVLinkProtocol::sendHeartbeat() ...@@ -390,14 +390,14 @@ void MAVLinkProtocol::sendHeartbeat()
mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, OCU, MAV_AUTOPILOT_GENERIC); mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, OCU, MAV_AUTOPILOT_GENERIC);
sendMessage(beat); sendMessage(beat);
} }
//if (m_authEnabled) { if (m_authEnabled) {
//mavlink_message_t msg; mavlink_message_t msg;
//mavlink_auth_key_t auth; 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); 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()); strcpy(auth.key, m_authKey.toStdString().c_str());
//mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth); mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
//sendMessage(msg); sendMessage(msg);
//} }
} }
/** @param enabled true to enable heartbeats emission at heartbeatRate, false to disable */ /** @param enabled true to enable heartbeats emission at heartbeatRate, false to disable */
......
...@@ -690,15 +690,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -690,15 +690,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
break; break;
//case MAVLINK_MSG_ID_SCALED_PRESSURE: { case MAVLINK_MSG_ID_SCALED_PRESSURE: {
//mavlink_scaled_pressure_t pressure; mavlink_scaled_pressure_t pressure;
//mavlink_msg_scaled_pressure_decode(&message, &pressure); mavlink_msg_scaled_pressure_decode(&message, &pressure);
//quint64 time = this->getUnixTime(pressure.usec); quint64 time = this->getUnixTime(pressure.usec);
//emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time); emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
//emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time); emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time);
//emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time); emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time);
//} }
//break; break;
case MAVLINK_MSG_ID_RC_CHANNELS_RAW: { case MAVLINK_MSG_ID_RC_CHANNELS_RAW: {
mavlink_rc_channels_raw_t channels; mavlink_rc_channels_raw_t channels;
...@@ -1975,24 +1975,24 @@ bool UAS::emergencyKILL() ...@@ -1975,24 +1975,24 @@ bool UAS::emergencyKILL()
void UAS::startHil() void UAS::startHil()
{ {
//mavlink_message_t msg; mavlink_message_t msg;
//// TODO Replace MG System ID with static function call and allow to change ID in GUI // 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); 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 // Send message twice to increase chance of reception
//sendMessage(msg); sendMessage(msg);
//sendMessage(msg); sendMessage(msg);
} }
void UAS::stopHil() void UAS::stopHil()
{ {
//mavlink_message_t msg; mavlink_message_t msg;
//// TODO Replace MG System ID with static function call and allow to change ID in GUI // 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); 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 // Send message twice to increase chance of reception
//sendMessage(msg); sendMessage(msg);
//sendMessage(msg); sendMessage(msg);
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment