Commit de6731dd authored by lm's avatar lm

Minor naming changes to MAVLink enum end

parent 76cfbbb9
...@@ -47,35 +47,35 @@ DEFINES += _TTY_NOWARN_ ...@@ -47,35 +47,35 @@ DEFINES += _TTY_NOWARN_
# MAC OS X # MAC OS X
macx { macx {
COMPILER_VERSION = $$system(gcc -v) # COMPILER_VERSION = $$system(gcc -v)
#message(Using compiler $$COMPILER_VERSION) #message(Using compiler $$COMPILER_VERSION)
CONFIG += x86 cocoa phonon CONFIG += x86 cocoa phonon
CONFIG -= x86_64 CONFIG -= x86_64
HARDWARE_PLATFORM = $$system(uname -a) #HARDWARE_PLATFORM = $$system(uname -a)
contains( $$HARDWARE_PLATFORM, "9.6.0" ) || contains( $$HARDWARE_PLATFORM, "9.7.0" ) || contains( $$HARDWARE_PLATFORM, "9.8.0" ) || contains( $$HARDWARE_PLATFORM, "9.9.0" ) { #contains( $$HARDWARE_PLATFORM, "9.6.0" ) || contains( $$HARDWARE_PLATFORM, "9.7.0" ) || contains( $$HARDWARE_PLATFORM, "9.8.0" ) || contains( $$HARDWARE_PLATFORM, "9.9.0" ) {
# x86 Mac OS X Leopard 10.5 and earlier # x86 Mac OS X Leopard 10.5 and earlier
#message(Building for Mac OS X 32bit/Leopard 10.5 and earlier) #message(Building for Mac OS X 32bit/Leopard 10.5 and earlier)
# Enable function-profiling with the OS X saturn tool # Enable function-profiling with the OS X saturn tool
debug { #debug {
#QMAKE_CXXFLAGS += -finstrument-functions #QMAKE_CXXFLAGS += -finstrument-functions
#LIBS += -lSaturn #LIBS += -lSaturn
CONFIG += console # CONFIG += console
} #}
} else { #} else {
# x64 Mac OS X Snow Leopard 10.6 and later # x64 Mac OS X Snow Leopard 10.6 and later
CONFIG += x86_64 x86 cocoa phonon # CONFIG += x86_64 x86 cocoa phonon
#CONFIG -= x86 # phonon #CONFIG -= x86 # phonon
#message(Building for Mac OS X 64bit/Snow Leopard 10.6 and later) #message(Building for Mac OS X 64bit/Snow Leopard 10.6 and later)
debug { # debug {
#QMAKE_CXXFLAGS += -finstrument-functions #QMAKE_CXXFLAGS += -finstrument-functions
#LIBS += -lSaturn #LIBS += -lSaturn
CONFIG += console CONFIG += console
} # }
} #}
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.5 QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.5
......
...@@ -32,7 +32,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -32,7 +32,7 @@ This file is part of the QGROUNDCONTROL project
#include "Waypoint.h" #include "Waypoint.h"
#include <QStringList> #include <QStringList>
Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _yaw, bool _autocontinue, bool _current, double _orbit, int _holdTime, MAV_FRAME _frame, MAV_COMMAND _action) Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _yaw, bool _autocontinue, bool _current, double _orbit, int _holdTime, MAV_FRAME _frame, MAV_CMD _action)
: id(_id), : id(_id),
x(_x), x(_x),
y(_y), y(_y),
...@@ -75,7 +75,7 @@ bool Waypoint::load(QTextStream &loadStream) ...@@ -75,7 +75,7 @@ bool Waypoint::load(QTextStream &loadStream)
{ {
this->id = wpParams[0].toInt(); this->id = wpParams[0].toInt();
this->frame = (MAV_FRAME) wpParams[1].toInt(); this->frame = (MAV_FRAME) wpParams[1].toInt();
this->action = (MAV_COMMAND) wpParams[2].toInt(); this->action = (MAV_CMD) wpParams[2].toInt();
this->param1 = wpParams[3].toDouble(); this->param1 = wpParams[3].toDouble();
this->param2 = wpParams[4].toDouble(); this->param2 = wpParams[4].toDouble();
this->orbit = wpParams[5].toDouble(); this->orbit = wpParams[5].toDouble();
...@@ -136,14 +136,14 @@ void Waypoint::setYaw(double yaw) ...@@ -136,14 +136,14 @@ void Waypoint::setYaw(double yaw)
void Waypoint::setAction(int action) void Waypoint::setAction(int action)
{ {
if (this->action != (MAV_COMMAND)action) if (this->action != (MAV_CMD)action)
{ {
this->action = (MAV_COMMAND)action; this->action = (MAV_CMD)action;
emit changed(this); emit changed(this);
} }
} }
void Waypoint::setAction(MAV_COMMAND action) void Waypoint::setAction(MAV_CMD action)
{ {
if (this->action != action) if (this->action != action)
{ {
......
...@@ -45,7 +45,7 @@ class Waypoint : public QObject ...@@ -45,7 +45,7 @@ class Waypoint : public QObject
public: public:
Waypoint(quint16 id = 0, double x = 0.0f, double y = 0.0f, double z = 0.0f, double yaw = 0.0f, bool autocontinue = false, Waypoint(quint16 id = 0, double x = 0.0f, double y = 0.0f, double z = 0.0f, double yaw = 0.0f, bool autocontinue = false,
bool current = false, double orbit = 0.15f, int holdTime = 0, bool current = false, double orbit = 0.15f, int holdTime = 0,
MAV_FRAME frame=MAV_FRAME_GLOBAL, MAV_COMMAND action=MAV_CMD_NAV_WAYPOINT); MAV_FRAME frame=MAV_FRAME_GLOBAL, MAV_CMD action=MAV_CMD_NAV_WAYPOINT);
~Waypoint(); ~Waypoint();
quint16 getId() const { return id; } quint16 getId() const { return id; }
...@@ -67,7 +67,7 @@ public: ...@@ -67,7 +67,7 @@ public:
double getParam7() const { return z; } double getParam7() const { return z; }
int getTurns() const { return param1; } int getTurns() const { return param1; }
MAV_FRAME getFrame() const { return frame; } MAV_FRAME getFrame() const { return frame; }
MAV_COMMAND getAction() const { return action; } MAV_CMD getAction() const { return action; }
const QString& getName() const { return name; } const QString& getName() const { return name; }
void save(QTextStream &saveStream); void save(QTextStream &saveStream);
...@@ -81,7 +81,7 @@ protected: ...@@ -81,7 +81,7 @@ protected:
double z; double z;
double yaw; double yaw;
MAV_FRAME frame; MAV_FRAME frame;
MAV_COMMAND action; MAV_CMD action;
bool autocontinue; bool autocontinue;
bool current; bool current;
double orbit; double orbit;
...@@ -98,7 +98,7 @@ public slots: ...@@ -98,7 +98,7 @@ public slots:
void setYaw(double yaw); void setYaw(double yaw);
/** @brief Set the waypoint action */ /** @brief Set the waypoint action */
void setAction(int action); void setAction(int action);
void setAction(MAV_COMMAND action); void setAction(MAV_CMD action);
void setFrame(MAV_FRAME frame); void setFrame(MAV_FRAME frame);
void setAutocontinue(bool autoContinue); void setAutocontinue(bool autoContinue);
void setCurrent(bool current); void setCurrent(bool current);
......
...@@ -247,11 +247,11 @@ bool MAVLinkXMLParser::generate() ...@@ -247,11 +247,11 @@ bool MAVLinkXMLParser::generate()
// Everything sane, starting with enum content // Everything sane, starting with enum content
currEnum = "enum " + enumName.toUpper() + "\n{\n"; currEnum = "enum " + enumName.toUpper() + "\n{\n";
currEnumEnd = QString("\n%1_ENUM_END\n};\n\n").arg(enumName.toUpper()); currEnumEnd = QString("\t%1_ENUM_END\n};\n\n").arg(enumName.toUpper());
int nextEnumValue = 0; int nextEnumValue = 0;
// Get the message fields // Get the enum fields
QDomNode f = e.firstChild(); QDomNode f = e.firstChild();
while (!f.isNull()) while (!f.isNull())
{ {
...@@ -298,8 +298,9 @@ bool MAVLinkXMLParser::generate() ...@@ -298,8 +298,9 @@ bool MAVLinkXMLParser::generate()
} }
// Add the last parsed enum // Add the last parsed enum
// Remove the last comma, as the last value has none // Remove the last comma, as the last value has none
int commaPosition = currEnum.lastIndexOf(","); // ENUM END MARKER IS LAST ENTRY, COMMA REMOVAL NOT NEEDED
currEnum.remove(commaPosition, 1); //int commaPosition = currEnum.lastIndexOf(",");
//currEnum.remove(commaPosition, 1);
enums += "/** @brief " + comment + " */\n" + currEnum + currEnumEnd; enums += "/** @brief " + comment + " */\n" + currEnum + currEnumEnd;
} // Element is non-zero and element name is <enum> } // Element is non-zero and element name is <enum>
......
...@@ -138,8 +138,8 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_ ...@@ -138,8 +138,8 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
if(wp->seq == current_wp_id) 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_COMMAND) 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 << (MAV_FRAME) wp->frame << (MAV_CMD) wp->command;
Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param4, wp->autocontinue, wp->current, wp->param1, wp->param2, (MAV_FRAME) wp->frame, (MAV_COMMAND) wp->command); Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param4, wp->autocontinue, wp->current, wp->param1, wp->param2, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);
addWaypoint(lwp, false); addWaypoint(lwp, false);
//get next waypoint //get next waypoint
......
...@@ -179,7 +179,21 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName, ...@@ -179,7 +179,21 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
// Get component // Get component
if (!components->contains(component)) if (!components->contains(component))
{ {
addComponent(uas, component, "Component #" + QString::number(component)); QString componentName;
switch (component)
{
case MAV_COMP_ID_CAMERA:
componentName = tr("Camera (#%1)").arg(component);
break;
case MAV_COMP_ID_IMU:
componentName = tr("IMU (#%1)").arg(component);
break;
default:
componentName = tr("Component #").arg(component);
break;
}
addComponent(uas, component, componentName);
} }
// Replace value in map // Replace value in map
...@@ -227,7 +241,9 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName, ...@@ -227,7 +241,9 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
QStringList plist; QStringList plist;
plist.append(parameterName); plist.append(parameterName);
plist.append(QString::number(value)); plist.append(QString::number(value));
// CREATE PARAMETER ITEM
parameterItem = new QTreeWidgetItem(plist); parameterItem = new QTreeWidgetItem(plist);
// CONFIGURE PARAMETER ITEM
compParamGroups->value(parent)->addChild(parameterItem); compParamGroups->value(parent)->addChild(parameterItem);
parameterItem->setFlags(parameterItem->flags() | Qt::ItemIsEditable); parameterItem->setFlags(parameterItem->flags() | Qt::ItemIsEditable);
...@@ -256,7 +272,9 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName, ...@@ -256,7 +272,9 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
QStringList plist; QStringList plist;
plist.append(parameterName); plist.append(parameterName);
plist.append(QString::number(value)); plist.append(QString::number(value));
// CREATE PARAMETER ITEM
parameterItem = new QTreeWidgetItem(plist); parameterItem = new QTreeWidgetItem(plist);
// CONFIGURE PARAMETER ITEM
components->value(component)->addChild(parameterItem); components->value(component)->addChild(parameterItem);
parameterItem->setFlags(parameterItem->flags() | Qt::ItemIsEditable); parameterItem->setFlags(parameterItem->flags() | Qt::ItemIsEditable);
...@@ -356,7 +374,9 @@ void QGCParamWidget::saveParameters() ...@@ -356,7 +374,9 @@ void QGCParamWidget::saveParameters()
QMap<QString, float>::iterator j; QMap<QString, float>::iterator j;
for (j = comp->begin(); j != comp->end(); ++j) for (j = comp->begin(); j != comp->end(); ++j)
{ {
in << mav->getUASID() << "\t" << compid << "\t" << j.key() << "\t" << j.value() << "\n"; QString paramValue("%1");
paramValue = paramValue.arg(j.value(), 18, 'g');
in << mav->getUASID() << "\t" << compid << "\t" << j.key() << "\t" << paramValue << "\n";
in.flush(); in.flush();
} }
} }
......
...@@ -42,7 +42,7 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) : ...@@ -42,7 +42,7 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
m_ui->comboBox_action->addItem(tr("Loiter Turns"),MAV_CMD_NAV_LOITER_TURNS); m_ui->comboBox_action->addItem(tr("Loiter Turns"),MAV_CMD_NAV_LOITER_TURNS);
m_ui->comboBox_action->addItem(tr("Return to Launch"),MAV_CMD_NAV_RETURN_TO_LAUNCH); m_ui->comboBox_action->addItem(tr("Return to Launch"),MAV_CMD_NAV_RETURN_TO_LAUNCH);
m_ui->comboBox_action->addItem(tr("Land"),MAV_CMD_NAV_LAND); m_ui->comboBox_action->addItem(tr("Land"),MAV_CMD_NAV_LAND);
m_ui->comboBox_action->addItem(tr("Other"), MAV_COMMAND_ENUM_END); m_ui->comboBox_action->addItem(tr("Other"), MAV_CMD_ENUM_END);
// m_ui->comboBox_action->addItem(tr("Delay"), MAV_ACTION_DELAY_BEFORE_COMMAND); // m_ui->comboBox_action->addItem(tr("Delay"), MAV_ACTION_DELAY_BEFORE_COMMAND);
// m_ui->comboBox_action->addItem(tr("Ascend/Descent"), MAV_ACTION_ASCEND_AT_RATE); // m_ui->comboBox_action->addItem(tr("Ascend/Descent"), MAV_ACTION_ASCEND_AT_RATE);
// m_ui->comboBox_action->addItem(tr("Change Mode"), MAV_ACTION_CHANGE_MODE); // m_ui->comboBox_action->addItem(tr("Change Mode"), MAV_ACTION_CHANGE_MODE);
...@@ -226,9 +226,9 @@ void WaypointView::changedAction(int index) ...@@ -226,9 +226,9 @@ void WaypointView::changedAction(int index)
{ {
// set waypoint action // set waypoint action
int actionIndex = m_ui->comboBox_action->itemData(index).toUInt(); int actionIndex = m_ui->comboBox_action->itemData(index).toUInt();
if (actionIndex < MAV_COMMAND_ENUM_END && actionIndex >= 0) if (actionIndex < MAV_CMD_ENUM_END && actionIndex >= 0)
{ {
MAV_COMMAND action = (MAV_COMMAND) actionIndex; MAV_CMD action = (MAV_CMD) actionIndex;
wp->setAction(action); wp->setAction(action);
} }
...@@ -245,14 +245,14 @@ void WaypointView::changedAction(int index) ...@@ -245,14 +245,14 @@ void WaypointView::changedAction(int index)
case MAV_CMD_NAV_LOITER_UNLIM: case MAV_CMD_NAV_LOITER_UNLIM:
case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_LOITER_TURNS:
case MAV_CMD_NAV_LOITER_TIME: case MAV_CMD_NAV_LOITER_TIME:
case MAV_CMD_NAV_DELAY: case MAV_CMD_CONDITION_DELAY:
case MAV_CMD_SYS_SET_MODE: case MAV_CMD_DO_SET_MODE:
// Back to global frame // Back to global frame
if (wp->getFrame() == MAV_FRAME_MISSION) changedFrame(0); if (wp->getFrame() == MAV_FRAME_MISSION) changedFrame(0);
// Update view // Update view
updateActionView(actionIndex); updateActionView(actionIndex);
break; break;
case MAV_COMMAND_ENUM_END: case MAV_CMD_ENUM_END:
default: default:
// Switch to mission frame // Switch to mission frame
changedFrame(MAV_FRAME_MISSION); changedFrame(MAV_FRAME_MISSION);
...@@ -411,12 +411,12 @@ void WaypointView::updateValues() ...@@ -411,12 +411,12 @@ void WaypointView::updateValues()
} }
// Update action // Update action
MAV_COMMAND action = wp->getAction(); MAV_CMD action = wp->getAction();
int action_index = m_ui->comboBox_action->findData(action); int action_index = m_ui->comboBox_action->findData(action);
// Set to "Other" action if it was -1 // Set to "Other" action if it was -1
if (action_index == -1) if (action_index == -1)
{ {
action_index = m_ui->comboBox_action->findData(MAV_COMMAND_ENUM_END); action_index = m_ui->comboBox_action->findData(MAV_CMD_ENUM_END);
} }
// Only update if changed // Only update if changed
if (m_ui->comboBox_action->currentIndex() != action_index) if (m_ui->comboBox_action->currentIndex() != action_index)
......
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