Browse Source

Merge branch 'experimental' of 128.168.1.167:/malife/qgroundcontrol into experimental

QGC4.4
tecnosapiens 15 years ago
parent
commit
fd514fecc5
  1. 10
      src/comm/MAVLinkSimulationLink.cc
  2. 4
      src/uas/PxQuadMAV.cc
  3. 2
      src/ui/linechart/LinechartWidget.cc
  4. 2
      src/ui/map3D/QOSGWidget.h

10
src/comm/MAVLinkSimulationLink.cc

@ -559,14 +559,14 @@ void MAVLinkSimulationLink::mainloop()
// Send controller states // Send controller states
uint8_t attControl = 1; // uint8_t attControl = 1;
uint8_t posXYControl = 1; // uint8_t posXYControl = 1;
uint8_t posZControl = 0; // uint8_t posZControl = 0;
uint8_t posYawControl = 1; // uint8_t posYawControl = 1;
uint8_t gpsLock = 2; uint8_t gpsLock = 2;
uint8_t visLock = 3; uint8_t visLock = 3;
uint8_t posLock = qMax(gpsLock, visLock); //uint8_t posLock = qMax(gpsLock, visLock);
#ifdef MAVLINK_ENABLED_PIXHAWK #ifdef MAVLINK_ENABLED_PIXHAWK
messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl); messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl);

4
src/uas/PxQuadMAV.cc

@ -168,5 +168,9 @@ void PxQuadMAV::sendProcessCommand(int watchdogId, int processId, unsigned int c
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_watchdog_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &payload); mavlink_msg_watchdog_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &payload);
sendMessage(msg); sendMessage(msg);
#else
Q_UNUSED(watchdogId);
Q_UNUSED(processId);
Q_UNUSED(command);
#endif #endif
} }

2
src/ui/linechart/LinechartWidget.cc

@ -352,8 +352,6 @@ QWidget* LinechartWidget::createCurveItem(QString curve)
QLabel* label; QLabel* label;
QLabel* value; QLabel* value;
QLabel* mean; QLabel* mean;
QLabel* median;
form->setAutoFillBackground(false); form->setAutoFillBackground(false);
horizontalLayout = new QHBoxLayout(form); horizontalLayout = new QHBoxLayout(form);
horizontalLayout->setSpacing(5); horizontalLayout->setSpacing(5);

2
src/ui/map3D/QOSGWidget.h

@ -123,7 +123,7 @@ public:
getCamera()->setGraphicsContext(getGraphicsWindow()); getCamera()->setGraphicsContext(getGraphicsWindow());
} }
virtual void paintEvent( QPaintEvent * event ) { frame(); } virtual void paintEvent( QPaintEvent * event ) { Q_UNUSED(event); frame(); }
protected: protected:

Loading…
Cancel
Save