Commit 1c4982e5 authored by pixhawk's avatar pixhawk

Cleaned up folder structure, finished toolbar

parent 771f2ace
# Onboard parameters for system BRAVO
#
# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT)
42 1 HANDLEWPDELAY 0.20000000298
42 1 POSFILTER 1
42 1 PROTDELAY 40
42 1 PROTTIMEOUT 2
42 1 SETPOINTDELAY 1
42 1 YAWTOLERANCE 0.174500003457
42 200 ACC_NAV_OFFS_X 0
42 200 ACC_NAV_OFFS_Y 0
42 200 ACC_NAV_OFFS_Z -1000
42 200 ATT_KAL_KACC 0.00329999998212
42 200 ATT_KAL_YAWMOD 3
42 200 ATT_OFFSET_X 0
42 200 ATT_OFFSET_Y 0
42 200 ATT_OFFSET_Z 0
42 200 CAL_ACC_X 0
42 200 CAL_ACC_Y 0
42 200 CAL_ACC_Z 0
42 200 CAL_FIT_ACTIVE 0
42 200 CAL_FIT_GYRO_X 31496.8007812
42 200 CAL_FIT_GYRO_Y 29383.4003906
42 200 CAL_FIT_GYRO_Z 30151.0996094
42 200 CAL_GYRO_X 29760
42 200 CAL_GYRO_Y 29671
42 200 CAL_GYRO_Z 29572
42 200 CAL_MAG_X 375
42 200 CAL_MAG_Y -25
42 200 CAL_MAG_Z -1000
42 200 CAL_PRES_DIFF 10000
42 200 CAL_TEMP 29557
42 200 CAM_ANG_X_FAC 0
42 200 CAM_ANG_X_OFF 0
42 200 CAM_ANG_Y_FAC 0
42 200 CAM_ANG_Y_OFF 0.81099998951
42 200 CAM_EXP 1000
42 200 CAM_INTERVAL 200000
42 200 DEBUG_1 0
42 200 DEBUG_2 0
42 200 DEBUG_3 0
42 200 DEBUG_4 0
42 200 DEBUG_5 1
42 200 DEBUG_6 0
42 200 GPS_MODE 0
42 200 KAL_VEL_AX 1
42 200 KAL_VEL_AY 1
42 200 KAL_VEL_BX 0
42 200 KAL_VEL_BY 0
42 200 MIX_OFFSET 1
42 200 MIX_POSITION 1
42 200 MIX_POS_YAW 1
42 200 MIX_REMOTE 0
42 200 MIX_Z_POSITION 1
42 200 PID_ATT_AWU 0.300000011921
42 200 PID_ATT_D 30
42 200 PID_ATT_I 60
42 200 PID_ATT_LIM 100
42 200 PID_ATT_P 90
42 200 PID_POS_AWU 5
42 200 PID_POS_D 2.20000004768
42 200 PID_POS_I 0.10000000149
42 200 PID_POS_LIM 0.20000000298
42 200 PID_POS_P 2
42 200 PID_POS_Z_AWU 3
42 200 PID_POS_Z_D 0.25
42 200 PID_POS_Z_I 0.300000011921
42 200 PID_POS_Z_LIM 0.300000011921
42 200 PID_POS_Z_P 0.25
42 200 PID_YAWPOS_AWU 1
42 200 PID_YAWPOS_D 1
42 200 PID_YAWPOS_I 0.10000000149
42 200 PID_YAWPOS_LIM 3
42 200 PID_YAWPOS_P 5
42 200 PID_YAWSPEED_D 0
42 200 PID_YAWSPEED_I 5
42 200 PID_YAWSPEED_P 15
42 200 PID_YAWSPE_AWU 1
42 200 PID_YAWSPE_LIM 50
42 200 POS_ESTIM_MODE 1
42 200 POS_HOV_TRUST 0.550000011921
42 200 POS_SON_MODE 0
42 200 POS_SON_SCALE 1
42 200 POS_SP_ACCEPT 1
42 200 POS_SP_X -0.0329026989639
42 200 POS_SP_Y -0.0478124991059
42 200 POS_SP_YAW 0
42 200 POS_SP_Z -0.643148005009
42 200 POS_TIMEOUT 2000000
42 200 POS_YAW_TRACK 0
42 200 RC_NICK_CHAN 1
42 200 RC_ROLL_CHAN 2
42 200 RC_SAFETY_CHAN 6
42 200 RC_THRUST_CHAN 3
42 200 RC_TRIM_CHAN 0
42 200 RC_TUNE_CHAN1 5
42 200 RC_TUNE_CHAN2 6
42 200 RC_TUNE_CHAN3 7
42 200 RC_TUNE_CHAN4 5
42 200 RC_YAW_CHAN 4
42 200 SEND_DEBUGCHAN 0
42 200 SLOT_ATTITUDE 1
42 200 SLOT_CONTROL 0
42 200 SLOT_RAW_IMU 0
42 200 SLOT_RC 1
42 200 SYS_COMP_ID 200
42 200 SYS_ID 42
42 200 SYS_IMU_RESET 0
42 200 SYS_SW_VER 2000
42 200 SYS_TYPE 2
42 200 UART_0_BAUD 115200
42 200 UART_1_BAUD 115200
42 200 VEL_DAMP 0.949999988079
42 200 VEL_OFFSET_X 0
42 200 VEL_OFFSET_Y 0
42 200 VEL_OFFSET_Z 0
42 200 VICON_TKO_DIST 0.5
42 200 VICON_TKO_TIME 2
42 200 VIS_OUTL_TRESH 0.20000000298
......@@ -44,7 +44,7 @@ warnVoltage(9.5f),
warnLevelPercent(20.0f),
currentVoltage(12.0f),
lpVoltage(12.0f),
batteryRemainingEstimateEnabled(false),
batteryRemainingEstimateEnabled(true),
mode(-1),
status(-1),
navMode(-1),
......@@ -2091,67 +2091,6 @@ void UAS::receiveButton(int buttonIndex)
}
/*void UAS::requestWaypoints()
{
// mavlink_message_t msg;
// mavlink_msg_waypoint_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 25);
// // Send message twice to increase chance of reception
// sendMessage(msg);
waypointManager.requestWaypoints();
qDebug() << "UAS Request WPs";
}
void UAS::setWaypoint(Waypoint* wp)
{
// mavlink_message_t msg;
// mavlink_waypoint_set_t set;
// set.id = wp->id;
// //QString name = wp->name;
// // FIXME Check if this works properly
// //name.truncate(MAVLINK_MSG_WAYPOINT_SET_FIELD_NAME_LEN);
// //strcpy((char*)set.name, name.toStdString().c_str());
// set.autocontinue = wp->autocontinue;
// set.target_component = 25; // FIXME
// set.target_system = uasId;
// set.active = wp->current;
// set.x = wp->x;
// set.y = wp->y;
// set.z = wp->z;
// set.yaw = wp->yaw;
// mavlink_msg_waypoint_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &set);
// // Send message twice to increase chance of reception
// sendMessage(msg);
}
void UAS::setWaypointActive(int id)
{
// mavlink_message_t msg;
// mavlink_waypoint_set_active_t active;
// active.id = id;
// active.target_system = uasId;
// active.target_component = 25; // FIXME
// mavlink_msg_waypoint_set_active_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &active);
// // Send message twice to increase chance of reception
// sendMessage(msg);
// sendMessage(msg);
// // TODO This should be not directly emitted, but rather being fed back from the UAS
// emit waypointSelected(getUASID(), id);
}
void UAS::clearWaypointList()
{
// mavlink_message_t msg;
// // FIXME
// mavlink_waypoint_clear_list_t clist;
// clist.target_system = uasId;
// clist.target_component = 25; // FIXME
// mavlink_msg_waypoint_clear_list_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &clist);
// sendMessage(msg);
// qDebug() << "UAS clears Waypoints!";
}*/
void UAS::halt()
{
mavlink_message_t msg;
......
......@@ -49,6 +49,8 @@ UASWaypointManager::UASWaypointManager(UAS &_uas)
protocol_timer(this)
{
connect(&protocol_timer, SIGNAL(timeout()), this, SLOT(timeout()));
connect(&uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleLocalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(&uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,quint64)));
}
void UASWaypointManager::timeout()
......@@ -86,6 +88,25 @@ void UASWaypointManager::timeout()
}
}
void UASWaypointManager::handleLocalPositionChanged(UASInterface* mav, double x, double y, double z, quint64 time)
{
Q_UNUSED(mav);
Q_UNUSED(time);
if (waypoints.count() > 0 && (waypoints[current_wp_id]->getFrame() == MAV_FRAME_LOCAL || waypoints[current_wp_id]->getFrame() == MAV_FRAME_LOCAL_ENU))
{
double xdiff = x-waypoints[current_wp_id]->getX();
double ydiff = y-waypoints[current_wp_id]->getY();
double zdiff = z-waypoints[current_wp_id]->getZ();
double dist = sqrt(xdiff*xdiff + ydiff*ydiff + zdiff*zdiff);
emit waypointDistanceChanged(dist);
}
}
void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double alt, quint64 time)
{
}
void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, quint16 count)
{
if (current_state == WP_GETLIST && systemId == current_partner_systemid && compId == current_partner_compid) {
......
......@@ -38,6 +38,7 @@ This file is part of the QGROUNDCONTROL project
#include "Waypoint.h"
#include "QGCMAVLink.h"
class UAS;
class UASInterface;
/**
* @brief Implementation of the MAVLINK waypoint protocol
......@@ -138,6 +139,8 @@ public slots:
void loadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile
void notifyOfChange(Waypoint* wp); ///< Notifies manager to changes to a waypoint
/*@}*/
void handleLocalPositionChanged(UASInterface* mav, double x, double y, double z, quint64 time);
void handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double alt, quint64 time);
signals:
void waypointListChanged(void); ///< emits signal that the waypoint list has been changed
......@@ -145,6 +148,7 @@ signals:
void waypointChanged(int uasid, Waypoint* wp); ///< emits signal that waypoint has been changed
void currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number
void updateStatusString(const QString &); ///< emits the current status string
void waypointDistanceChanged(double distance); ///< Distance to next waypoint changed (in meters)
void loadWPFile(); ///< emits signal that a file wp has been load
void readGlobalWPFromUAS(bool value); ///< emits signal when finish to read Global WP from UAS
......
......@@ -51,17 +51,21 @@ QGCToolBar::QGCToolBar(QWidget *parent) :
symbolButton = new QToolButton(this);
toolBarNameLabel = new QLabel("------", this);
toolBarModeLabel = new QLabel("------", this);
toolBarModeLabel->setStyleSheet("QLabel { margin: 0px 4px; font: 16px; color: #3C7B9E; }");
toolBarModeLabel->setStyleSheet("QLabel { margin: 0px 4px; font: 14px; color: #3C7B9E; }");
toolBarStateLabel = new QLabel("------", this);
toolBarStateLabel->setStyleSheet("QLabel { margin: 0px 4px; font: 16px; color: #FEC654; }");
toolBarWpLabel = new QLabel("---", this);
toolBarStateLabel->setStyleSheet("QLabel { margin: 0px 4px; font: 14px; color: #FEC654; }");
toolBarWpLabel = new QLabel("WP--", this);
toolBarWpLabel->setStyleSheet("QLabel { margin: 0px 4px; font: 18px; color: #3C7B9E; }");
toolBarDistLabel = new QLabel("--- ---- m", this);
toolBarMessageLabel = new QLabel("No system messages.", this);
toolBarMessageLabel->setStyleSheet("QLabel { margin: 0px 4px; font: 12px; font-style: italic; color: #3C7B9E; }");
toolBarBatteryBar = new QProgressBar(this);
toolBarBatteryBar->setStyleSheet("QProgressBar:horizontal { margin: 0px 8px; border: 1px solid #4A4A4F; border-radius: 4px; text-align: center; padding: 2px; color: #111111; background-color: #111118; height: 10px; } QProgressBar:horizontal QLabel { font-size: 9px; color: #111111; } QProgressBar::chunk { background-color: green; }");
toolBarBatteryBar->setStyleSheet("QProgressBar:horizontal { margin: 0px 4px 0px 0px; border: 1px solid #4A4A4F; border-radius: 4px; text-align: center; padding: 2px; color: #111111; background-color: #111118; height: 10px; } QProgressBar:horizontal QLabel { font-size: 9px; color: #111111; } QProgressBar::chunk { background-color: green; }");
toolBarBatteryBar->setMinimum(0);
toolBarBatteryBar->setMaximum(100);
toolBarBatteryBar->setMaximumWidth(200);
toolBarBatteryVoltageLabel = new QLabel("xx.x V");
toolBarBatteryVoltageLabel->setStyleSheet(QString("QLabel { margin: 0px 2px 0px 4px; font: 14px; color: %1; }").arg(QColor(Qt::green).name()));
//symbolButton->setIcon(":");
symbolButton->setStyleSheet("QWidget { background-color: #050508; color: #DDDDDF; background-clip: border; } QToolButton { font-weight: bold; font-size: 12px; border: 0px solid #999999; border-radius: 5px; min-width:22px; max-width: 22px; min-height: 22px; max-height: 22px; padding: 0px; margin: 0px 0px 0px 20px; background-color: none; }");
addWidget(symbolButton);
......@@ -69,6 +73,7 @@ QGCToolBar::QGCToolBar(QWidget *parent) :
addWidget(toolBarModeLabel);
addWidget(toolBarStateLabel);
addWidget(toolBarBatteryBar);
addWidget(toolBarBatteryVoltageLabel);
addWidget(toolBarWpLabel);
addWidget(toolBarDistLabel);
addWidget(toolBarMessageLabel);
......@@ -137,6 +142,11 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
disconnect(mav, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
disconnect(mav, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(receiveTextMessage(int,int,int,QString)));
disconnect(mav, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int)));
if (mav->getWaypointManager())
{
disconnect(mav->getWaypointManager(), SIGNAL(currentWaypointChanged(int)), this, SLOT(updateCurrentWaypoint(int)));
disconnect(mav->getWaypointManager(), SIGNAL(waypointDistanceChanged(double)), this, SLOT(updateWaypointDistance(double)));
}
}
// Connect new system
......@@ -147,6 +157,11 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
connect(active, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
connect(active, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(receiveTextMessage(int,int,int,QString)));
connect(active, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int)));
if (active->getWaypointManager())
{
connect(active->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(updateCurrentWaypoint(quint16)));
connect(active->getWaypointManager(), SIGNAL(waypointDistanceChanged(double)), this, SLOT(updateWaypointDistance(double)));
}
// Update all values once
toolBarNameLabel->setText(mav->getUASName());
......@@ -164,9 +179,22 @@ void QGCToolBar::createCustomWidgets()
}
void QGCToolBar::updateWaypointDistance(double distance)
{
toolBarDistLabel->setText(tr("%1 m").arg(distance, 6, 'f', 2, '0'));
}
void QGCToolBar::updateCurrentWaypoint(quint16 id)
{
toolBarWpLabel->setText(tr("WP%1").arg(id));
}
void QGCToolBar::updateBatteryRemaining(UASInterface* uas, double voltage, double percent, int seconds)
{
Q_UNUSED(uas);
Q_UNUSED(seconds);
toolBarBatteryBar->setValue(percent);
toolBarBatteryVoltageLabel->setText(tr("%1 V").arg(voltage, 4, 'f', 1, ' '));
}
void QGCToolBar::updateState(UASInterface* system, QString name, QString description)
......
......@@ -60,6 +60,10 @@ public slots:
void setLogPlayer(QGCMAVLinkLogPlayer* player);
/** @brief Update battery charge state */
void updateBatteryRemaining(UASInterface* uas, double voltage, double percent, int seconds);
/** @brief Update current waypoint */
void updateCurrentWaypoint(quint16 id);
/** @brief Update distance to current waypoint */
void updateWaypointDistance(double distance);
protected:
void createCustomWidgets();
......@@ -75,6 +79,7 @@ protected:
QLabel* toolBarDistLabel;
QLabel* toolBarMessageLabel;
QProgressBar* toolBarBatteryBar;
QLabel* toolBarBatteryVoltageLabel;
};
#endif // QGCTOOLBAR_H
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