Commit 7303d617 authored by lm's avatar lm

A number of bugfixes for various MAVLink messages

parent 9af2c59b
*Makefile* *Makefile*
tags tags
build build
Info.plist Info.plist
obj obj
*.log *.log
*~ *~
*qtc* *qtc*
bin/*.exe bin/*.exe
bin/*.txt bin/*.txt
bin/mac bin/mac
*pro.user* *pro.user*
qrc_*.cpp qrc_*.cpp
*.Debug *.Debug
*.Release *.Release
tmp tmp
debug debug
release release
qgroundcontrol qgroundcontrol
mavlinkgen mavlinkgen
*.wav *.wav
qgroundcontrol.xcodeproj/** qgroundcontrol.xcodeproj/**
doc/html doc/html
doc/doxy.log doc/doxy.log
deploy/mac deploy/mac
deploy/linux deploy/linux
controller_log* deploy/qgroundcontrol*
user_config.pri controller_log*
*.app user_config.pri
*.app
*.ncb *.ncb
*.vcproj *.vcproj
...@@ -39,4 +40,4 @@ user_config.pri ...@@ -39,4 +40,4 @@ user_config.pri
*.project *.project
*.cproject *.cproject
*.sln *.sln
*.suo *.suo
\ No newline at end of file
#!/bin/sh #!/bin/sh
# Clean build directories cp -r ../../qgroundcontrol-build-desktop/qgroundcontrol.app .
rm -rf mac
mkdir -p mac
# Change to build directory and compile application
cd ..
make -j4
# Copy and build the application bundle
cd deploy
cp -r ../bin/mac/qgroundcontrol.app mac/.
cp -r ../audio mac/qgroundcontrol.app/Contents/MacOs/. cp -r ../audio qgroundcontrol.app/Contents/MacOs/.
mkdir -p mac/qgroundcontrol.app/Contents/Frameworks/ mkdir -p qgroundcontrol.app/Contents/Frameworks/
# SDL is not copied by Qt - for whatever reason # SDL is not copied by Qt - for whatever reason
cp -r SDL.framework mac/qgroundcontrol.app/Contents/Frameworks/. cp -r /Library/Frameworks/SDL.framework qgroundcontrol.app/Contents/Frameworks/.
echo -e '\n\nStarting to create disk image. This may take a while..\n' echo -e '\n\nStarting to create disk image. This may take a while..\n'
macdeployqt mac/qgroundcontrol.app -dmg macdeployqt qgroundcontrol.app -dmg
rm -rf mac/qgroundcontrol.app #rm -rf qgroundcontrol.app
echo -e '\n\n QGroundControl .DMG file is now ready for publishing\n' echo -e '\n\n QGroundControl .DMG file is now ready for publishing\n'
...@@ -50,11 +50,13 @@ macx { ...@@ -50,11 +50,13 @@ macx {
COMPILER_VERSION = $$system(gcc -v) COMPILER_VERSION = $$system(gcc -v)
#message(Using compiler $$COMPILER_VERSION) #message(Using compiler $$COMPILER_VERSION)
CONFIG += x86 cocoa phonon
CONFIG -= x86_64
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 x86_64 cocoa phonon
#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
......
...@@ -143,9 +143,13 @@ void MAVLinkSimulationMAV::mainloop() ...@@ -143,9 +143,13 @@ void MAVLinkSimulationMAV::mainloop()
// ATTITUDE // ATTITUDE
mavlink_attitude_t attitude; mavlink_attitude_t attitude;
attitude.usec = 0;
attitude.roll = 0.0f; attitude.roll = 0.0f;
attitude.pitch = 0.0f; attitude.pitch = 0.0f;
attitude.yaw = yaw; attitude.yaw = yaw;
attitude.rollspeed = 0.0f;
attitude.pitchspeed = 0.0f;
attitude.yawspeed = 0.0f;
mavlink_msg_attitude_encode(systemid, MAV_COMP_ID_IMU, &msg, &attitude); mavlink_msg_attitude_encode(systemid, MAV_COMP_ID_IMU, &msg, &attitude);
link->sendMAVLinkMessage(&msg); link->sendMAVLinkMessage(&msg);
...@@ -158,7 +162,7 @@ void MAVLinkSimulationMAV::mainloop() ...@@ -158,7 +162,7 @@ void MAVLinkSimulationMAV::mainloop()
status.packet_drop = 0; status.packet_drop = 0;
status.vbat = 10500; status.vbat = 10500;
status.status = sys_state; status.status = sys_state;
status.battery_remaining = 900;
mavlink_msg_sys_status_encode(systemid, MAV_COMP_ID_IMU, &msg, &status); mavlink_msg_sys_status_encode(systemid, MAV_COMP_ID_IMU, &msg, &status);
link->sendMAVLinkMessage(&msg); link->sendMAVLinkMessage(&msg);
timer10Hz = 5; timer10Hz = 5;
...@@ -183,8 +187,19 @@ void MAVLinkSimulationMAV::mainloop() ...@@ -183,8 +187,19 @@ void MAVLinkSimulationMAV::mainloop()
nav.wp_dist = 2.0f; nav.wp_dist = 2.0f;
nav.alt_error = 0.5f; nav.alt_error = 0.5f;
nav.xtrack_error = 0.2f; nav.xtrack_error = 0.2f;
nav.aspd_error = 0.0f;
mavlink_msg_nav_controller_output_encode(systemid, MAV_COMP_ID_IMU, &msg, &nav); mavlink_msg_nav_controller_output_encode(systemid, MAV_COMP_ID_IMU, &msg, &nav);
link->sendMAVLinkMessage(&msg); link->sendMAVLinkMessage(&msg);
// RAW PRESSURE
mavlink_raw_pressure_t pressure;
pressure.press_abs = 1000;
pressure.press_diff1 = 2000;
pressure.press_diff2 = 5000;
pressure.temperature = 18150; // 18.15 deg Celsius
pressure.usec = 0; // Works also with zero timestamp
mavlink_msg_raw_pressure_encode(systemid, MAV_COMP_ID_IMU, &msg, &pressure);
link->sendMAVLinkMessage(&msg);
} }
// 25 Hz execution // 25 Hz execution
...@@ -203,6 +218,7 @@ void MAVLinkSimulationMAV::mainloop() ...@@ -203,6 +218,7 @@ void MAVLinkSimulationMAV::mainloop()
control_status.gps_fix = 2; // 2D GPS fix control_status.gps_fix = 2; // 2D GPS fix
control_status.position_fix = 3; // 3D fix from GPS + barometric pressure control_status.position_fix = 3; // 3D fix from GPS + barometric pressure
control_status.vision_fix = 0; // no fix from vision system control_status.vision_fix = 0; // no fix from vision system
control_status.ahrs_health = 230;
mavlink_msg_control_status_encode(systemid, MAV_COMP_ID_IMU, &ret, &control_status); mavlink_msg_control_status_encode(systemid, MAV_COMP_ID_IMU, &ret, &control_status);
link->sendMAVLinkMessage(&ret); link->sendMAVLinkMessage(&ret);
#endif //MAVLINK_ENABLED_PIXHAWK #endif //MAVLINK_ENABLED_PIXHAWK
......
...@@ -620,10 +620,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -620,10 +620,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{ {
mavlink_raw_pressure_t pressure; mavlink_raw_pressure_t pressure;
mavlink_msg_raw_pressure_decode(&message, &pressure); mavlink_msg_raw_pressure_decode(&message, &pressure);
quint64 time = this->getUnixTime(0); quint64 time = this->getUnixTime(pressure.usec);
emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time); emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
emit valueChanged(uasId, "diff pressure 1", "hPa", pressure.press_diff1, time); emit valueChanged(uasId, "diff pressure 1", "hPa", pressure.press_diff1, time);
emit valueChanged(uasId, "diff pressure 2", "hPa", pressure.press_diff2, time); emit valueChanged(uasId, "diff pressure 2", "hPa", pressure.press_diff2, time);
emit valueChanged(uasId, "temperature", "deg C", pressure.temperature/100.0f, time);
} }
break; break;
case MAVLINK_MSG_ID_RC_CHANNELS_RAW: case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
......
...@@ -97,7 +97,7 @@ void QGCRemoteControlView::setUASId(int id) ...@@ -97,7 +97,7 @@ void QGCRemoteControlView::setUASId(int id)
{ {
// The UAS exists, disconnect any existing connections // The UAS exists, disconnect any existing connections
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float,float)), this, SLOT(setChannel(int,float,float))); disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
disconnect(uas, SIGNAL(remoteControlRSSIRawChanged(float)), this, SLOT(setRemoteRSSI(float))); disconnect(uas, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer<RadioCalibrationData>)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&))); disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer<RadioCalibrationData>)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float))); disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
disconnect(uas, SIGNAL(remoteControlChannelScaledChanged(int,float,float)), calibrationWindow, SLOT(setChannelScaled(int,float))); disconnect(uas, SIGNAL(remoteControlChannelScaledChanged(int,float,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
...@@ -116,9 +116,7 @@ void QGCRemoteControlView::setUASId(int id) ...@@ -116,9 +116,7 @@ void QGCRemoteControlView::setUASId(int id)
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float))); connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float))); connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float))); connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float)));
// connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
} }
} }
...@@ -205,6 +203,8 @@ void QGCRemoteControlView::redraw() ...@@ -205,6 +203,8 @@ void QGCRemoteControlView::redraw()
{ {
progressBars.at(i)->setValue(normalized.at(i)*100.0f); progressBars.at(i)->setValue(normalized.at(i)*100.0f);
} }
// Update RSSI
rssiBar->setValue(rssi*100);
updated = false; updated = false;
} }
} }
......
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