Commit 7fa3071d authored by lm's avatar lm

Improved line chart, brought back movement on HUD (but still looks somewhat...

Improved line chart, brought back movement on HUD (but still looks somewhat wrong on the dials). Fixed logging for ground time mode
parent 9a11483b
......@@ -214,7 +214,7 @@ void LogCompressor::run()
}
}
if (index % (dataLines/100) == 0) emit logProcessingStatusChanged(tr("Log compressor: Processed %1% of %2 lines").arg(index/(float)dataLines*100, 0, 'f', 2).arg(dataLines));
if (dataLines > 100) if (index % (dataLines/100) == 0) emit logProcessingStatusChanged(tr("Log compressor: Processed %1% of %2 lines").arg(index/(float)dataLines*100, 0, 'f', 2).arg(dataLines));
if (!failed)
{
......
......@@ -375,13 +375,20 @@ void MAVLinkSimulationLink::mainloop()
{
rate10hzCounter = 1;
float lastX = x;
float lastY = y;
float lastZ = z;
float hackDt = 0.1f; // 100 ms
// Move X Position
x = 12.0*sin(((double)circleCounter)/100.0);
y = 5.0*cos(((double)circleCounter)/100.0);
z = 1.8 + 1.2*sin(((double)circleCounter)/60.0);
float xSpeed = (x - lastX)/hackDt;
float ySpeed = (y - lastY)/hackDt;
float zSpeed = (z - lastZ)/hackDt;
circleCounter++;
......@@ -402,7 +409,7 @@ void MAVLinkSimulationLink::mainloop()
streampointer += bufferlength;
// Send back new position
mavlink_msg_local_position_pack(systemId, componentId, &ret, 0, x, y, -fabs(z), 0, 0, 0);
mavlink_msg_local_position_pack(systemId, componentId, &ret, 0, x, y, -fabs(z), xSpeed, ySpeed, zSpeed);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
......@@ -416,14 +423,14 @@ void MAVLinkSimulationLink::mainloop()
// streampointer += bufferlength;
// GLOBAL POSITION
mavlink_msg_global_position_int_pack(systemId, componentId, &ret, (473780.28137103+(x))*1E3, (85489.9892510421+(y))*1E3, (z+550.0)*1000.0, 0*100.0, 0*100.0, 0*100.0);
mavlink_msg_global_position_int_pack(systemId, componentId, &ret, (473780.28137103+(x))*1E3, (85489.9892510421+(y))*1E3, (z+550.0)*1000.0, xSpeed*15.0*100.0, ySpeed*15.0*100.0, zSpeed*15*100.0);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// GLOBAL POSITION VEHICLE 2
mavlink_msg_global_position_int_pack(54, componentId, &ret, (473780.28137103+(x+0.002))*1E3, (85489.9892510421+((y/2)+0.3))*1E3, (z+570.0)*1000.0, 0*100.0, 0*100.0, 0*100.0);
mavlink_msg_global_position_int_pack(54, componentId, &ret, (473780.28137103+(x+0.002))*1E3, (85489.9892510421+((y/2)+0.3))*1E3, (z+570.0)*1000.0, xSpeed*15.0*100.0, ySpeed*15.0*100.0, zSpeed*15.0*100.0);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
......
......@@ -464,7 +464,7 @@ bool MAVLinkXMLParser::generate()
// Add field to C structure
cStructLines += QString("\t%1 %2[%3]; ///< %4\n").arg(arrayType, fieldName, QString::number(arrayLength), fieldText);
// Add pack line to message_xx_pack function
packLines += QString("\ti += put_array_by_index((int8_t*)%1, sizeof(%2)*%3, i, msg->payload); // %4\n").arg(fieldName, arrayType, QString::number(arrayLength), fieldText);
packLines += QString("\ti += put_array_by_index((const int8_t*)%1, sizeof(%2)*%3, i, msg->payload); // %4\n").arg(fieldName, arrayType, QString::number(arrayLength), fieldText);
// Add decode function for this type
decodeLines += QString("\tmavlink_msg_%1_get_%2(msg, %1->%2);\n").arg(messageName, fieldName);
arrayDefines += QString("#define MAVLINK_MSG_%1_FIELD_%2_LEN %3\n").arg(messageName.toUpper(), fieldName.toUpper(), QString::number(arrayLength));
......
......@@ -60,8 +60,8 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_raw_aux_t raw;
mavlink_msg_raw_aux_decode(&message, &raw);
quint64 time = getUnixTime(0);
emit valueChanged(uasId, "Pressure", raw.baro, time);
emit valueChanged(uasId, "Temperature", raw.temp, time);
emit valueChanged(uasId, "Pressure", "raw", raw.baro, time);
emit valueChanged(uasId, "Temperature", "raw", raw.temp, time);
}
break;
case MAVLINK_MSG_ID_PATTERN_DETECTED:
......@@ -110,12 +110,12 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_msg_vision_position_estimate_decode(&message, &pos);
quint64 time = getUnixTime(pos.usec);
//emit valueChanged(uasId, "vis. time", pos.usec, time);
emit valueChanged(uasId, "vis. roll", pos.roll, time);
emit valueChanged(uasId, "vis. pitch", pos.pitch, time);
emit valueChanged(uasId, "vis. yaw", pos.yaw, time);
emit valueChanged(uasId, "vis. x", pos.x, time);
emit valueChanged(uasId, "vis. y", pos.y, time);
emit valueChanged(uasId, "vis. z", pos.z, time);
emit valueChanged(uasId, "vis. roll", "rad", pos.roll, time);
emit valueChanged(uasId, "vis. pitch", "rad", pos.pitch, time);
emit valueChanged(uasId, "vis. yaw", "rad", pos.yaw, time);
emit valueChanged(uasId, "vis. x", "rad/s", pos.x, time);
emit valueChanged(uasId, "vis. y", "rad/s", pos.y, time);
emit valueChanged(uasId, "vis. z", "rad/s", pos.z, time);
}
break;
case MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE:
......@@ -124,12 +124,12 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_msg_vicon_position_estimate_decode(&message, &pos);
quint64 time = getUnixTime(pos.usec);
//emit valueChanged(uasId, "vis. time", pos.usec, time);
emit valueChanged(uasId, "vicon roll", pos.roll, time);
emit valueChanged(uasId, "vicon pitch", pos.pitch, time);
emit valueChanged(uasId, "vicon yaw", pos.yaw, time);
emit valueChanged(uasId, "vicon x", pos.x, time);
emit valueChanged(uasId, "vicon y", pos.y, time);
emit valueChanged(uasId, "vicon z", pos.z, time);
emit valueChanged(uasId, "vicon roll", "rad", pos.roll, time);
emit valueChanged(uasId, "vicon pitch", "rad", pos.pitch, time);
emit valueChanged(uasId, "vicon yaw", "rad", pos.yaw, time);
emit valueChanged(uasId, "vicon x", "rad/s", pos.x, time);
emit valueChanged(uasId, "vicon y", "rad/s", pos.y, time);
emit valueChanged(uasId, "vicon z", "rad/s", pos.z, time);
emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
}
break;
......@@ -143,7 +143,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit errCountChanged(uasId, "IMU", "SPI0", status.spi0_err_count);
emit errCountChanged(uasId, "IMU", "SPI1", status.spi1_err_count);
emit errCountChanged(uasId, "IMU", "UART", status.uart_total_err_count);
emit UAS::valueChanged(this, "Load", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "Load", "%", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow());
}
break;
case MAVLINK_MSG_ID_CONTROL_STATUS:
......
This diff is collapsed.
......@@ -328,9 +328,9 @@ signals:
* @param msec the timestamp of the message, in milliseconds
*/
// FIXME Exchange the lines below against the commented ones
void valueChanged(int uasId, QString name, double value, quint64 msec);
void valueChanged(UASInterface* uas, QString name, double value, quint64 msec);
//void valueChanged(const int uasId, const QString& name, const double value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const int value, const quint64 msec);
// void valueChanged(const int uasId, const QString& name, const double value, const quint64 msec);
// //void valueChanged(UASInterface* uas, QString name, double value, quint64 msec);
......
......@@ -250,6 +250,10 @@ void HUD::setActiveUAS(UASInterface* uas)
disconnect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString)));
disconnect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
disconnect(uas, SIGNAL(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*)));
disconnect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
disconnect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
disconnect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int)));
}
// Now connect the new UAS
......@@ -260,11 +264,15 @@ void HUD::setActiveUAS(UASInterface* uas)
connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
connect(uas, SIGNAL(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*)));
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int)));
// Set new UAS
this->uas = uas;
}
void HUD::updateAttitudeThrustSetPoint(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 msec)
void HUD::updateAttitudeThrustSetPoint(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 msec)
{
updateValue(uas, "roll desired", rollDesired, msec);
updateValue(uas, "pitch desired", pitchDesired, msec);
......@@ -711,7 +719,9 @@ void HUD::paintHUD()
QString yawAngle;
// const float yawDeg = ((values.value("yaw", 0.0f)/M_PI)*180.0f)+180.f;
const float yawDeg = ((values.value("yaw", 0.0f)/M_PI)*180.0f);
// YAW is in compass-human readable format, so 0 - 360deg. This is normal in aviation, not -180 - +180.
const float yawDeg = ((values.value("yaw", 0.0f)/M_PI)*180.0f)+180.0f;
yawAngle.sprintf("%03d", (int)yawDeg);
paintText(yawAngle, defaultColor, 3.5f, -3.7f, compassY+ 0.9f, &painter);
......@@ -730,6 +740,9 @@ void HUD::paintHUD()
drawChangeIndicatorGauge(vGaugeSpacing, -15.0f, 10.0f, 5.0f, values.value("xSpeed", 0.0f), defaultColor, &painter, false);
// Waypoint name
if (waypointName != "") paintText(waypointName, defaultColor, 2.0f, (-vwidth/3.0) + 10, +vheight/3.0 + 15, &painter);
// MOVING PARTS
......@@ -1351,12 +1364,10 @@ void HUD::resizeGL(int w, int h)
paintHUD();
}
void HUD::selectWaypoint(UASInterface* uas, int id)
void HUD::selectWaypoint(int uasId, int id)
{
if (uas == this->uas)
{
waypointName = tr("WP") + QString::number(id);
}
Q_UNUSED(uasId);
waypointName = tr("WP") + QString::number(id);
}
void HUD::setImageSize(int width, int height, int depth, int channels)
......
......@@ -77,7 +77,7 @@ public slots:
void updateState(UASInterface*,QString);
void updateMode(int id,QString mode, QString description);
void updateLoad(UASInterface*, double);
void selectWaypoint(UASInterface* uas, int id);
void selectWaypoint(int uasId, int id);
void startImage(int imgid, int width, int height, int depth, int channels);
void setPixels(int imgid, const unsigned char* imageData, int length, int startIndex);
......
......@@ -628,7 +628,6 @@ void MainWindow::showToolWidget()
QAction* temp = qobject_cast<QAction *>(sender());
int tool = temp->data().toInt();
if (temp && dockWidgets[tool])
{
if (temp->isChecked())
......@@ -640,9 +639,6 @@ void MainWindow::showToolWidget()
{
removeDockWidget(qobject_cast<QDockWidget *>(dockWidgets[tool]));
}
QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast<TOOLS_WIDGET_NAMES>(tool), currentView);
settings.setValue(chKey,temp->isChecked());
settings.sync();
}
}
......@@ -1306,6 +1302,25 @@ void MainWindow::clearView()
// Save current state
if (UASManager::instance()->getActiveUAS()) settings.setValue(getWindowStateKey(), saveState(QGC::applicationVersion()));
settings.setValue(getWindowGeometryKey(), saveGeometry());
QAction* temp;
// Set tool widget visibility settings for this view
foreach (int key, toolsMenuActions.keys())
{
temp = toolsMenuActions[key];
QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast<TOOLS_WIDGET_NAMES>(key), currentView);
if (temp)
{
settings.setValue(chKey,temp->isChecked());
}
else
{
settings.setValue(chKey,false);
}
}
settings.sync();
// Remove all dock widgets from main window
......@@ -1500,8 +1515,13 @@ void MainWindow::showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SE
void MainWindow::loadDataView(QString fileName)
{
clearView();
// Unload line chart
QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast<TOOLS_WIDGET_NAMES>(CENTRAL_LINECHART), currentView);
settings.setValue(chKey,false);
// Set data plot in settings as current widget and then run usual update procedure
QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast<TOOLS_WIDGET_NAMES>(CENTRAL_DATA_PLOT), currentView);
chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast<TOOLS_WIDGET_NAMES>(CENTRAL_DATA_PLOT), currentView);
settings.setValue(chKey,true);
presentView();
......
......@@ -228,7 +228,8 @@ void LinechartPlot::appendData(QString dataname, quint64 ms, double value)
datalock.lock();
/* Check if dataset identifier already exists */
if(!data.contains(dataname)) {
if(!data.contains(dataname))
{
addCurve(dataname);
}
......
This diff is collapsed.
......@@ -70,9 +70,14 @@ public:
static const int MAX_TIME_SCROLLBAR_VALUE = 16383; ///< The maximum scrollbar value
public slots:
void addCurve(QString curve);
void addCurve(const QString& curve, const QString& unit);
void removeCurve(QString curve);
/** @brief Append data without unit */
void appendData(int uasId, QString curve, double data, quint64 usec);
/** @brief Append data with unit */
void appendData(int uasId, const QString& curve, const QString& unit, double value, quint64 usec);
/** @brief Append data as int with unit */
void appendData(int uasId, const QString& curve, const QString& unit, int value, quint64 usec);
void takeButtonClick(bool checked);
void setPlotWindowPosition(int scrollBarValue);
void setPlotWindowPosition(quint64 position);
......@@ -110,6 +115,7 @@ protected:
QMap<QString, QLabel*>* curveMeans; ///< References to the curve means
QMap<QString, QLabel*>* curveMedians; ///< References to the curve medians
QMap<QString, QLabel*>* curveVariances; ///< References to the curve variances
QMap<QString, int> intData; ///< Current values for integer-valued curves
QWidget* curvesWidget; ///< The QWidget containing the curve selection button
QGridLayout* curvesWidgetLayout; ///< The layout for the curvesWidget QWidget
......@@ -130,9 +136,9 @@ protected:
QFile* logFile;
unsigned int logindex;
bool logging;
quint64 logStartTime;
QTimer* updateTimer;
LogCompressor* compressor;
quint64 logStartTime;
static const int MAX_CURVE_MENUITEM_NUMBER = 8;
static const int PAGESTEP_TIME_SCROLLBAR_VALUE = (MAX_TIME_SCROLLBAR_VALUE - MIN_TIME_SCROLLBAR_VALUE) / 10;
......
......@@ -96,7 +96,12 @@ void Linecharts::addSystem(UASInterface* uas)
addWidget(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)));
// Values without unit
//connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), widget, SLOT(appendData(int,QString,double,quint64)));
// Values with unit as double
connect(uas, SIGNAL(valueChanged(int,QString,QString,double,quint64)), widget, SLOT(appendData(int,QString,QString,double,quint64)));
// Values with unit as integer
connect(uas, SIGNAL(valueChanged(int,QString,QString,double,quint64)), widget, SLOT(appendData(int,QString,QString,double,quint64)));
#endif
connect(widget, SIGNAL(logfileWritten(QString)), this, SIGNAL(logfileWritten(QString)));
// Set system active if this is the only system
......
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