Commit 359faf28 authored by lm's avatar lm

Folder structure cleanup, added APM tooltips

parent 0f7c4379
This diff is collapsed.
......@@ -66,10 +66,12 @@ MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile
onboardParams.insert("PID_ROLL_K_P", 0.5f);
onboardParams.insert("PID_PITCH_K_P", 0.5f);
onboardParams.insert("PID_YAW_K_P", 0.5f);
onboardParams.insert("PID_XY_K_P", 0.5f);
onboardParams.insert("PID_XY_K_P", 100.0f);
onboardParams.insert("PID_ALT_K_P", 0.5f);
onboardParams.insert("SYS_TYPE", 1);
onboardParams.insert("SYS_ID", systemId);
onboardParams.insert("RC4_REV", 0);
onboardParams.insert("RC5_REV", 1);
// Comments on the variables can be found in the header file
......
......@@ -68,7 +68,7 @@ void MAVLinkSimulationMAV::mainloop()
// 1 Hz execution
if (timer1Hz <= 0) {
mavlink_message_t msg;
mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_PIXHAWK, MAV_MODE_GUIDED, MAV_FLIGHT_MODE_AUTO_MISSION, MAV_STATE_ACTIVE, MAV_SAFETY_ARMED, 0xFF);
mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_MODE_GUIDED, MAV_FLIGHT_MODE_AUTO_MISSION, MAV_STATE_ACTIVE, MAV_SAFETY_ARMED, 0xFF);
link->sendMAVLinkMessage(&msg);
planner.handleMessage(msg);
......
......@@ -4,6 +4,7 @@
#include <QWidget>
#include <QMap>
#include <QTimer>
#include <QVariant>
class UASInterface;
......@@ -16,10 +17,10 @@ public:
QList<QString> getParameterNames(int component) const {
return parameters.value(component)->keys();
}
QList<float> getParameterValues(int component) const {
QList<QVariant> getParameterValues(int component) const {
return parameters.value(component)->values();
}
float getParameterValue(int component, const QString& parameter) const {
QVariant getParameterValue(int component, const QString& parameter) const {
return parameters.value(component)->value(parameter);
}
......@@ -29,23 +30,23 @@ public:
virtual void requestParameterUpdate(int component, const QString& parameter) = 0;
signals:
void parameterChanged(int component, QString parameter, float value);
void parameterChanged(int component, int parameterIndex, float value);
void parameterChanged(int component, QString parameter, QVariant value);
void parameterChanged(int component, int parameterIndex, QVariant value);
void parameterListUpToDate(int component);
public slots:
/** @brief Write one parameter to the MAV */
virtual void setParameter(int component, QString parameterName, float value) = 0;
virtual void setParameter(int component, QString parameterName, QVariant value) = 0;
/** @brief Request list of parameters from MAV */
virtual void requestParameterList() = 0;
protected:
UASInterface* mav; ///< The MAV this widget is controlling
QMap<int, QMap<QString, float>* > changedValues; ///< Changed values
QMap<int, QMap<QString, float>* > parameters; ///< All parameters
QMap<int, QMap<QString, QVariant>* > changedValues; ///< Changed values
QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
QVector<bool> received; ///< Successfully received parameters
QMap<int, QList<int>* > transmissionMissingPackets; ///< Missing packets
QMap<int, QMap<QString, float>* > transmissionMissingWriteAckPackets; ///< Missing write ACK packets
QMap<int, QMap<QString, QVariant>* > transmissionMissingWriteAckPackets; ///< Missing write ACK packets
bool transmissionListMode; ///< Currently requesting list
QMap<int, bool> transmissionListSizeKnown; ///< List size initialized?
bool transmissionActive; ///< Missing packets, working on list?
......
......@@ -743,21 +743,74 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
QByteArray bytes((char*)value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
QString parameterName = QString(bytes);
int component = message.compid;
float val = value.param_value;
mavlink_param_union_t val;
val.param_float = value.param_value;
// Convert to machine order if necessary
//#if MAVLINK_NEED_BYTE_SWAP
// buffer[bindex] = (b>>24)&0xff;
// buffer[bindex+1] = (b>>16)&0xff;
// buffer[bindex+2] = (b>>8)&0xff;
// buffer[bindex+3] = (b & 0xff);
//#else
// Insert component if necessary
if (!parameters.contains(component))
{
parameters.insert(component, new QMap<QString, float>());
parameters.insert(component, new QMap<QString, QVariant>());
}
// Insert parameter into registry
if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
parameters.value(component)->insert(parameterName, val);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val);
// Insert with correct type
switch (value.param_type)
{
case MAV_DATA_TYPE_FLOAT:
parameters.value(component)->insert(parameterName, val.param_float);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_float);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_float);
break;/*
case MAV_DATA_TYPE_UINT8:
parameters.value(component)->insert(parameterName, val.param_uint8);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_uint8);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint8);
break;
case MAV_DATA_TYPE_INT8:
parameters.value(component)->insert(parameterName, val.param_int8);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_int8);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int8);
break;
case MAV_DATA_TYPE_UINT16:
parameters.value(component)->insert(parameterName, val.param_uint16);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_uint16);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint16);
break;
case MAV_DATA_TYPE_INT16:
parameters.value(component)->insert(parameterName, val.param_int16);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_int16);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int16);
break;*/
case MAV_DATA_TYPE_UINT32:
parameters.value(component)->insert(parameterName, val.param_uint32);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_uint32);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint32);
break;
case MAV_DATA_TYPE_INT32:
parameters.value(component)->insert(parameterName, val.param_int32);
// Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_int32);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int32);
break;
default:
qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
}
}
break;
case MAVLINK_MSG_ID_COMMAND_ACK:
......@@ -1868,13 +1921,35 @@ void UAS::enableExtra3Transmission(int rate)
* @param id Name of the parameter
* @param value Parameter value
*/
void UAS::setParameter(const int component, const QString& id, const float value)
void UAS::setParameter(const int component, const QString& id, const QVariant& value)
{
if (!id.isNull())
{
mavlink_message_t msg;
mavlink_param_set_t p;
p.param_value = value;
mavlink_param_union_t union_value;
// Assign correct value based on QVariant
switch (value.type())
{
case QVariant::Int:
union_value.param_int32 = value.toInt();
p.param_type = MAV_DATA_TYPE_INT32;
break;
case QVariant::UInt:
union_value.param_uint32 = value.toUInt();
p.param_type = MAV_DATA_TYPE_UINT32;
break;
case QMetaType::Float:
union_value.param_float = value.toFloat();
p.param_type = MAV_DATA_TYPE_FLOAT;
break;
default:
qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
return;
}
p.param_value = union_value.param_float;
p.target_system = (uint8_t)uasId;
p.target_component = (uint8_t)component;
......
......@@ -200,7 +200,7 @@ protected: //COMMENTS FOR TEST UNIT
QImage image; ///< Image data of last completely transmitted image
quint64 imageStart;
QMap<int, QMap<QString, float>* > parameters; ///< All parameters
QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
bool paramsOnceRequested; ///< If the parameter list has been read at least once
int airframe; ///< The airframe type
bool attitudeKnown; ///< True if attitude was received, false else
......@@ -459,7 +459,7 @@ public slots:
void requestParameter(int component, int parameter);
/** @brief Set a system parameter */
void setParameter(const int component, const QString& id, const float value);
void setParameter(const int component, const QString& id, const QVariant& value);
/** @brief Write parameters to permanent storage */
void writeParametersToStorage();
......
......@@ -255,7 +255,7 @@ public slots:
* @warning The length of the ID string is limited by the MAVLink format! Take care to not exceed it
* @param value Value of the parameter, IEEE 754 single precision floating point
*/
virtual void setParameter(const int component, const QString& id, const float value) = 0;
virtual void setParameter(const int component, const QString& id, const QVariant& value) = 0;
/**
* @brief Add a link to the list of current links
......@@ -395,8 +395,8 @@ signals:
void waypointSelected(int uasId, int id);
void waypointReached(UASInterface* uas, int id);
void autoModeChanged(bool autoMode);
void parameterChanged(int uas, int component, QString parameterName, float value);
void parameterChanged(int uas, int component, int parameterCount, int parameterId, QString parameterName, float value);
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
void parameterChanged(int uas, int component, int parameterCount, int parameterId, QString parameterName, QVariant value);
void patternDetected(int uasId, QString patternPath, float confidence, bool detected);
void letterDetected(int uasId, QString letter, float confidence, bool detected);
/**
......
This diff is collapsed.
......@@ -52,22 +52,22 @@ public:
UASInterface* getUAS();
signals:
/** @brief A parameter was changed in the widget, NOT onboard */
void parameterChanged(int component, QString parametername, float value);
void parameterChanged(int component, QString parametername, QVariant value);
/** @brief Request a single parameter */
void requestParameter(int component, int parameter);
public slots:
/** @brief Add a component to the list */
void addComponent(int uas, int component, QString componentName);
/** @brief Add a parameter to the list with retransmission / safety checks */
void addParameter(int uas, int component, int paramCount, int paramId, QString parameterName, float value);
void addParameter(int uas, int component, int paramCount, int paramId, QString parameterName, QVariant value);
/** @brief Add a parameter to the list */
void addParameter(int uas, int component, QString parameterName, float value);
void addParameter(int uas, int component, QString parameterName, QVariant value);
/** @brief Request list of parameters from MAV */
void requestParameterList();
/** @brief Request one single parameter */
void requestParameterUpdate(int component, const QString& parameter);
/** @brief Set one parameter, changes value in RAM of MAV */
void setParameter(int component, QString parameterName, float value);
void setParameter(int component, QString parameterName, QVariant value);
/** @brief Set all parameters, changes the value in RAM of MAV */
void setParameters();
/** @brief Write the current parameters to permanent storage (EEPROM/HDD) */
......@@ -96,9 +96,9 @@ protected:
// Tooltip data structures
QMap<QString, QString> paramToolTips; ///< Tooltip values
// Min / Default / Max data structures
QMap<QString, float> paramMin; ///< Minimum param values
QMap<QString, float> paramDefault; ///< Default param values
QMap<QString, float> paramMax; ///< Minimum param values
QMap<QString, double> paramMin; ///< Minimum param values
QMap<QString, double> paramDefault; ///< Default param values
QMap<QString, double> paramMax; ///< Minimum param values
/** @brief Activate / deactivate parameter retransmission */
void setRetransmissionGuardEnabled(bool enabled);
......
......@@ -69,7 +69,7 @@ void UASControlWidget::setUAS(UASInterface* uas)
{
if (this->uas != 0) {
UASInterface* oldUAS = UASManager::instance()->getUASForId(this->uas);
disconnect(ui.controlButton, SIGNAL(clicked()), oldUAS, SLOT(enable_motors()));
disconnect(ui.controlButton, SIGNAL(clicked()), oldUAS, SLOT(armSystem()));
disconnect(ui.liftoffButton, SIGNAL(clicked()), oldUAS, SLOT(launch()));
disconnect(ui.landButton, SIGNAL(clicked()), oldUAS, SLOT(home()));
disconnect(ui.shutdownButton, SIGNAL(clicked()), oldUAS, SLOT(shutdown()));
......
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