Commit 855c376d authored by LM's avatar LM

Minor fixes

parent ddd6934a
......@@ -198,6 +198,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// }
//#endif
#ifdef QGC_PROTOBUF_ENABLED
if (message.msgid == MAVLINK_MSG_ID_EXTENDED_MESSAGE)
{
mavlink_extended_message_t extended_message;
......
......@@ -977,7 +977,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
#ifdef QGC_PROTOBUF_ENABLED
void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message)
{
if (!link) return;
if (!link)
{
return;
}
if (!links->contains(link))
{
addLink(link);
......
......@@ -61,6 +61,11 @@ UASWaypointManager::UASWaypointManager(UAS* _uas)
}
}
UASWaypointManager::~UASWaypointManager()
{
}
void UASWaypointManager::timeout()
{
if (current_retries > 0) {
......
......@@ -65,6 +65,7 @@ private:
public:
UASWaypointManager(UAS* uas=NULL); ///< Standard constructor
~UASWaypointManager();
/** @name Received message handlers */
/*@{*/
......
......@@ -155,7 +155,10 @@ void WaypointList::updateAttitude(UASInterface* uas, double roll, double pitch,
void WaypointList::setUAS(UASInterface* uas)
{
//if (this->uas == NULL && uas != NULL)
if (this->uas == NULL && uas != NULL)
{
WPM = uas->getWaypointManager();
}
if (this->uas == NULL)
{
this->uas = uas;
......
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