Commit 18dc426f authored by pixhawk's avatar pixhawk

Added GPS support

parent 77ec7b8e
......@@ -19,6 +19,9 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
UAS::receiveMessage(link, message);
mavlink_message_t* msg = &message;
qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid;
// Handle your special messages
switch (msg->msgid)
{
......
......@@ -117,6 +117,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
addLink(link);
}
qDebug() << "UAS RECEIVED" << message.sysid << message.compid << message.msgid;
if (message.sysid == uasId)
{
QString uasState;
......@@ -368,13 +370,16 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
mavlink_gps_raw_t pos;
mavlink_msg_gps_raw_decode(&message, &pos);
quint64 time = getUnixTime(pos.usec);
// quint64 time = getUnixTime(pos.usec);
quint64 time = MG::TIME::getGroundTimeNow();
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);
qDebug() << "GOT GPS RAW";
emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
}
break;
case MAVLINK_MSG_ID_PARAM_VALUE:
......
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