Commit 6679ac37 authored by lm's avatar lm

Fixed master branch

parent fe401d20
...@@ -48,14 +48,14 @@ DEFINES += _TTY_NOWARN_ ...@@ -48,14 +48,14 @@ DEFINES += _TTY_NOWARN_
macx { macx {
COMPILER_VERSION = $$system(gcc -v) COMPILER_VERSION = $$system(gcc -v)
message(Using compiler $$COMPILER_VERSION) #message(Using compiler $$COMPILER_VERSION)
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
CONFIG += x86 cocoa phonon CONFIG += x86 x86_64 cocoa phonon
CONFIG -= x86_64 #CONFIG -= x86_64
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 {
...@@ -65,9 +65,9 @@ macx { ...@@ -65,9 +65,9 @@ macx {
} }
} 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 cocoa CONFIG += x86_64 x86 cocoa
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
......
...@@ -114,7 +114,6 @@ void MAVLinkSimulationLink::run() ...@@ -114,7 +114,6 @@ void MAVLinkSimulationLink::run()
status.mode = MAV_MODE_UNINIT; status.mode = MAV_MODE_UNINIT;
status.status = MAV_STATE_UNINIT; status.status = MAV_STATE_UNINIT;
status.vbat = 0; status.vbat = 0;
status.motor_block = 1;
status.packet_drop = 0; status.packet_drop = 0;
...@@ -619,8 +618,9 @@ void MAVLinkSimulationLink::mainloop() ...@@ -619,8 +618,9 @@ void MAVLinkSimulationLink::mainloop()
uint8_t gpsLock = 2; uint8_t gpsLock = 2;
uint8_t visLock = 3; uint8_t visLock = 3;
uint8_t ahrsHealth = 200;
uint8_t posLock = qMax(gpsLock, visLock); uint8_t posLock = qMax(gpsLock, visLock);
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, ahrsHealth, attControl,posXYControl, posZControl, posYawControl);
#endif #endif
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
......
...@@ -140,7 +140,6 @@ void MAVLinkSimulationMAV::mainloop() ...@@ -140,7 +140,6 @@ void MAVLinkSimulationMAV::mainloop()
// SYSTEM STATUS // SYSTEM STATUS
mavlink_sys_status_t status; mavlink_sys_status_t status;
status.load = 300; status.load = 300;
status.motor_block = 1;
status.mode = sys_mode; status.mode = sys_mode;
status.nav_mode = nav_mode; status.nav_mode = nav_mode;
status.packet_drop = 0; status.packet_drop = 0;
......
...@@ -251,11 +251,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -251,11 +251,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
getStatusForCode((int)state.status, uasState, stateDescription); getStatusForCode((int)state.status, uasState, stateDescription);
emit statusChanged(this, uasState, stateDescription); emit statusChanged(this, uasState, stateDescription);
emit statusChanged(this->status); emit statusChanged(this->status);
emit loadChanged(this,state.load/10.0f);
emit valueChanged(uasId, "Load", "%", ((float)state.load)/1000.0f, MG::TIME::getGroundTimeNow());
stateAudio = " changed status to " + uasState; stateAudio = " changed status to " + uasState;
} }
emit loadChanged(this,state.load/10.0f);
emit valueChanged(uasId, "Load", "%", ((float)state.load)/1000.0f, getUnixTime());
if (this->mode != static_cast<unsigned int>(state.mode)) if (this->mode != static_cast<unsigned int>(state.mode))
{ {
modechanged = true; modechanged = true;
......
...@@ -317,7 +317,7 @@ signals: ...@@ -317,7 +317,7 @@ signals:
protected: protected:
/** @brief Get the UNIX timestamp in microseconds */ /** @brief Get the UNIX timestamp in microseconds */
quint64 getUnixTime(quint64 time); quint64 getUnixTime(quint64 time=0);
protected slots: protected slots:
/** @brief Write settings to disk */ /** @brief Write settings to disk */
......
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