Browse Source

Cleanup of airframe config, removed debug line

QGC4.4
Lorenz Meier 12 years ago
parent
commit
b82d37f818
  1. 2
      src/comm/MAVLinkProtocol.cc
  2. 10
      src/ui/px4_configuration/QGCPX4AirframeConfig.cc

2
src/comm/MAVLinkProtocol.cc

@ -539,7 +539,7 @@ void MAVLinkProtocol::sendMessage(mavlink_message_t message) @@ -539,7 +539,7 @@ void MAVLinkProtocol::sendMessage(mavlink_message_t message)
for (i = links.begin(); i != links.end(); ++i)
{
sendMessage(*i, message);
qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
// qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
}
}

10
src/ui/px4_configuration/QGCPX4AirframeConfig.cc

@ -301,7 +301,7 @@ void QGCPX4AirframeConfig::checkConfigState() @@ -301,7 +301,7 @@ void QGCPX4AirframeConfig::checkConfigState()
// Reboot
//TODO right now this relies upon the above send & persist finishing before the reboot command is received...
unsigned pendingMax = 20;
unsigned pendingMax = 17;
qDebug() << "PENDING PARAMS REBOOT BEFORE" << pendingParams;
@ -338,14 +338,6 @@ void QGCPX4AirframeConfig::checkConfigState() @@ -338,14 +338,6 @@ void QGCPX4AirframeConfig::checkConfigState()
qDebug() << "CONNECT AIRFRAME";
LinkManager::instance()->connectAll();
}
if (pendingParams == 15) {
qDebug() << "DISCONNECT AIRFRAME";
LinkManager::instance()->disconnectAll();
}
if (pendingParams == 16) {
qDebug() << "CONNECT AIRFRAME";
LinkManager::instance()->connectAll();
}
if (pendingParams < pendingMax) {
progress->setValue(pendingParams);

Loading…
Cancel
Save