Commit ee9cbf32 authored by Mariano Lizarraga's avatar Mariano Lizarraga

Working on having Slugs comply with the WP protocol

parent d4303c21
...@@ -89,8 +89,8 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P ...@@ -89,8 +89,8 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
} }
#else #else
// *nix (Linux, MacOS tested) serial port support // *nix (Linux, MacOS tested) serial port support
//port = new QextSerialPort(porthandle, QextSerialPort::Polling); port = new QextSerialPort(porthandle, QextSerialPort::Polling);
port = new QextSerialPort(porthandle, QextSerialPort::EventDriven); //port = new QextSerialPort(porthandle, QextSerialPort::EventDriven);
port->setTimeout(timeout); // Timeout of 0 ms, we don't want to wait for data, we just poll again next time port->setTimeout(timeout); // Timeout of 0 ms, we don't want to wait for data, we just poll again next time
port->setBaudRate(baudrate); port->setBaudRate(baudrate);
port->setFlowControl(flow); port->setFlowControl(flow);
......
...@@ -59,77 +59,13 @@ SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) : ...@@ -59,77 +59,13 @@ SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{ {
// Let UAS handle the default message set // Let UAS handle the default message set
// UAS::receiveMessage(link, message); UAS::receiveMessage(link, message);
// Handle your special messages mavlink_message_t* msg = &message; // Handle your special messages mavlink_message_t* msg = &message;
switch (message.msgid) switch (message.msgid)
{ {
case MAVLINK_MSG_ID_HEARTBEAT:
emit heartbeat(this);
// Set new type if it has changed
if (this->type != mavlink_msg_heartbeat_get_type(&message))
{
this->type = mavlink_msg_heartbeat_get_type(&message);
emit systemTypeSet(this, type);
}
break;
case MAVLINK_MSG_ID_RAW_IMU:
mavlink_msg_raw_imu_decode(&message, &mlRawImuData);
break;
case MAVLINK_MSG_ID_WAYPOINT_COUNT:
mavlink_waypoint_count_t wpct;
mavlink_msg_waypoint_count_decode(&message, &wpct);
if (wpct.target_system == mavlink->getSystemId() && wpct.target_component == mavlink->getComponentId())
{
waypointManager.handleWaypointCount(message.sysid, message.compid, wpct.count);
}
break;
case MAVLINK_MSG_ID_WAYPOINT:
mavlink_waypoint_t wp;
mavlink_msg_waypoint_decode(&message, &wp);
//qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
{
waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
}
break;
case MAVLINK_MSG_ID_WAYPOINT_ACK:
mavlink_waypoint_ack_t wpa;
mavlink_msg_waypoint_ack_decode(&message, &wpa);
if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
{
waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
}
break;
case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
mavlink_waypoint_request_t wpr;
mavlink_msg_waypoint_request_decode(&message, &wpr);
qDebug() << "Waypoint Request" << wpr.seq;
if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
{
waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
}
break;
case MAVLINK_MSG_ID_WAYPOINT_REACHED:
mavlink_waypoint_reached_t wpre;
mavlink_msg_waypoint_reached_decode(&message, &wpre);
waypointManager.handleWaypointReached(message.sysid, message.compid, &wpre);
break;
case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
mavlink_waypoint_current_t wpc;
mavlink_msg_waypoint_current_decode(&message, &wpc);
waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
break;
#ifdef MAVLINK_ENABLED_SLUGS #ifdef MAVLINK_ENABLED_SLUGS
case MAVLINK_MSG_ID_BOOT: case MAVLINK_MSG_ID_BOOT:
......
...@@ -440,7 +440,6 @@ void UASWaypointManager::readWaypoints() ...@@ -440,7 +440,6 @@ void UASWaypointManager::readWaypoints()
void UASWaypointManager::writeWaypoints() void UASWaypointManager::writeWaypoints()
{ {
qDebug() << "+++++++++++++++++++>>>> Entro Funcion Write WP";
if (current_state == WP_IDLE) if (current_state == WP_IDLE)
{ {
if (waypoints.count() > 0) if (waypoints.count() > 0)
......
...@@ -490,6 +490,7 @@ void WaypointList::on_clearWPListButton_clicked() ...@@ -490,6 +490,7 @@ void WaypointList::on_clearWPListButton_clicked()
widget->remove(); widget->remove();
} }
uas->getWaypointManager().clearWaypointList();
isGlobalWP = false; isGlobalWP = false;
......
...@@ -54,7 +54,9 @@ void Linecharts::addSystem(UASInterface* uas) ...@@ -54,7 +54,9 @@ void Linecharts::addSystem(UASInterface* uas)
LinechartWidget* widget = new LinechartWidget(uas->getUASID(), this); LinechartWidget* widget = new LinechartWidget(uas->getUASID(), this);
addWidget(widget); addWidget(widget);
plots.insert(uas->getUASID(), widget); plots.insert(uas->getUASID(), widget);
#ifndef MAVLINK_ENABLED_SLUGS
connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), widget, SLOT(appendData(int,QString,double,quint64))); connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), widget, SLOT(appendData(int,QString,double,quint64)));
#endif
connect(widget, SIGNAL(logfileWritten(QString)), this, SIGNAL(logfileWritten(QString))); connect(widget, SIGNAL(logfileWritten(QString)), this, SIGNAL(logfileWritten(QString)));
// Set system active if this is the only system // Set system active if this is the only system
if (active) if (active)
......
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