Commit 3732645d authored by Mariano Lizarraga's avatar Mariano Lizarraga

Added support for parameter interface to SLUGS

parent de33002f
......@@ -90,10 +90,6 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_msg_gps_raw_decode(&message, &mlGpsData);
break;
case MAVLINK_MSG_ID_ACTION_ACK: // 62
mavlink_msg_action_ack_decode(&message,&mlActionAck);
break;
case MAVLINK_MSG_ID_CPU_LOAD: //170
mavlink_msg_cpu_load_decode(&message,&mlCpuLoadData);
break;
......@@ -151,6 +147,27 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
break;
case MAVLINK_MSG_ID_SLUGS_ACTION: //183
mavlink_msg_slugs_action_decode(&message, &mlAction);
switch (mlAction.actionId){
case SLUGS_ACTION_EEPROM:
if (mlAction.actionVal == SLUGS_ACTION_FAIL){
emit textMessageReceived(message.sysid, message.compid, 255, "EEPROM Write Fail, Data was not saved in Memory!");
}
break;
case SLUGS_ACTION_PT_CHANGE:
if (mlAction.actionVal == SLUGS_ACTION_SUCCESS){
emit textMessageReceived(message.sysid, message.compid, 0, "Passthrough Succesfully Changed");
}
break;
case SLUGS_ACTION_MLC_CHANGE:
if (mlAction.actionVal == SLUGS_ACTION_SUCCESS){
emit textMessageReceived(message.sysid, message.compid, 0, "Mid-level Commands Succesfully Changed");
}
break;
}// switch actionId
break;
......
......@@ -33,6 +33,25 @@ class SlugsMAV : public UAS
{
Q_OBJECT
Q_INTERFACES(UASInterface)
enum SLUGS_ACTION {
SLUGS_ACTION_NONE,
SLUGS_ACTION_SUCCESS,
SLUGS_ACTION_FAIL,
SLUGS_ACTION_EEPROM,
SLUGS_ACTION_MODE_CHANGE,
SLUGS_ACTION_MODE_REPORT,
SLUGS_ACTION_PT_CHANGE,
SLUGS_ACTION_PT_REPORT,
SLUGS_ACTION_PID_CHANGE,
SLUGS_ACTION_PID_REPORT,
SLUGS_ACTION_WP_CHANGE,
SLUGS_ACTION_WP_REPORT,
SLUGS_ACTION_MLC_CHANGE,
SLUGS_ACTION_MLC_REPORT
};
public:
SlugsMAV(MAVLinkProtocol* mavlink, int id = 0);
......
......@@ -138,7 +138,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
if(wp->seq == current_wp_id)
{
//qDebug() << "Got WP: " << wp->seq << wp->x << wp->y << wp->z << wp->param4 << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << (MAV_FRAME) wp->frame << (MAV_CMD) wp->command;
//qDebug() << "Got WP: " << wp->seq << wp->x << wp->y << wp->z << wp->param4 << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << "Frame:"<< (MAV_FRAME) wp->frame << "Command:" << (MAV_CMD) wp->command;
Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param1, wp->param2, wp->param3, wp->param4, wp->autocontinue, wp->current, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);
addWaypoint(lwp, false);
......
......@@ -35,7 +35,7 @@
<item row="0" column="0">
<widget class="QTabWidget" name="SlugsSensorView_tabWidget">
<property name="currentIndex">
<number>1</number>
<number>0</number>
</property>
<widget class="QWidget" name="tab">
<attribute name="title">
......
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