Commit edd5ae4d authored by pixhawk's avatar pixhawk

Merge branch 'v10release' of git://github.com/pixhawk/qgroundcontrol into offline-wplist

parents ae63c43c fdaca2c4
...@@ -120,7 +120,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint ...@@ -120,7 +120,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint
*/ */
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
{ {
memcpy(buffer, (uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len); memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len);
return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len;
} }
...@@ -182,7 +182,15 @@ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) ...@@ -182,7 +182,15 @@ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
*/ */
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
{ {
#if MAVLINK_EXTERNAL_RX_BUFFER
// No m_mavlink_message array defined in function,
// has to be defined externally
#ifndef m_mavlink_message
#error ERROR: IF #define MAVLINK_EXTERNAL_RX_BUFFER IS SET, THE BUFFER HAS TO BE ALLOCATED OUTSIDE OF THIS FUNCTION
#endif
#else
static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS]; static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS];
#endif
/* /*
default message crc function. You can override this per-system to default message crc function. You can override this per-system to
...@@ -209,6 +217,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa ...@@ -209,6 +217,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
{ {
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0; rxmsg->len = 0;
rxmsg->magic = c;
mavlink_start_checksum(rxmsg); mavlink_start_checksum(rxmsg);
} }
break; break;
...@@ -269,7 +278,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa ...@@ -269,7 +278,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
break; break;
case MAVLINK_PARSE_STATE_GOT_MSGID: case MAVLINK_PARSE_STATE_GOT_MSGID:
_MAV_PAYLOAD(rxmsg)[status->packet_idx++] = (char)c; _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
mavlink_update_checksum(rxmsg, c); mavlink_update_checksum(rxmsg, c);
if (status->packet_idx == rxmsg->len) if (status->packet_idx == rxmsg->len)
{ {
...@@ -296,6 +305,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa ...@@ -296,6 +305,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
else else
{ {
status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
} }
break; break;
...@@ -317,6 +327,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa ...@@ -317,6 +327,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
// Successfully got message // Successfully got message
status->msg_received = 1; status->msg_received = 1;
status->parse_state = MAVLINK_PARSE_STATE_IDLE; status->parse_state = MAVLINK_PARSE_STATE_IDLE;
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c;
memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
} }
break; break;
......
#ifndef MAVLINK_TYPES_H_ #ifndef MAVLINK_TYPES_H_
#define MAVLINK_TYPES_H_ #define MAVLINK_TYPES_H_
#include <inttypes.h>
enum MAV_ACTION enum MAV_ACTION
{ {
MAV_ACTION_HOLD = 0, MAV_ACTION_HOLD = 0,
...@@ -66,6 +68,8 @@ typedef struct param_union { ...@@ -66,6 +68,8 @@ typedef struct param_union {
float param_float; float param_float;
int32_t param_int32; int32_t param_int32;
uint32_t param_uint32; uint32_t param_uint32;
uint8_t param_uint8;
uint8_t bytes[4];
}; };
uint8_t type; uint8_t type;
} mavlink_param_union_t; } mavlink_param_union_t;
...@@ -107,12 +111,12 @@ typedef enum { ...@@ -107,12 +111,12 @@ typedef enum {
#define MAVLINK_MAX_FIELDS 64 #define MAVLINK_MAX_FIELDS 64
typedef struct __mavlink_field_info { typedef struct __mavlink_field_info {
const char *name; // name of this field const char *name; // name of this field
const char *print_format; // printing format hint, or NULL const char *print_format; // printing format hint, or NULL
mavlink_message_type_t type; // type of this field mavlink_message_type_t type; // type of this field
unsigned array_length; // if non-zero, field is an array unsigned int array_length; // if non-zero, field is an array
unsigned wire_offset; // offset of each field in the payload unsigned int wire_offset; // offset of each field in the payload
unsigned structure_offset; // offset in a C structure unsigned int structure_offset; // offset in a C structure
} mavlink_field_info_t; } mavlink_field_info_t;
// note that in this structure the order of fields is the order // note that in this structure the order of fields is the order
...@@ -123,11 +127,12 @@ typedef struct __mavlink_message_info { ...@@ -123,11 +127,12 @@ typedef struct __mavlink_message_info {
mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
} mavlink_message_info_t; } mavlink_message_info_t;
#define _MAV_PAYLOAD(msg) ((char *)(&(msg)->payload64[0])) #define _MAV_PAYLOAD(msg) ((const char *)(&(msg)->payload64[0]))
#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)((char *)(&(msg)->payload64[0])))
// checksum is immediately after the payload bytes // checksum is immediately after the payload bytes
#define mavlink_ck_a(msg) *(msg->len + (uint8_t *)_MAV_PAYLOAD(msg)) #define mavlink_ck_a(msg) *(msg->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
#define mavlink_ck_b(msg) *((msg->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD(msg)) #define mavlink_ck_b(msg) *((msg->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
typedef enum { typedef enum {
MAVLINK_COMM_0, MAVLINK_COMM_0,
......
...@@ -153,17 +153,25 @@ static inline void byte_copy_8(char *dst, const char *src) ...@@ -153,17 +153,25 @@ static inline void byte_copy_8(char *dst, const char *src)
#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b #define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b
#endif #endif
/*
like memcpy(), but if src is NULL, do a memset to zero
*/
static void mav_array_memcpy(void *dest, const void *src, size_t n)
{
if (src == NULL) {
memset(dest, 0, n);
} else {
memcpy(dest, src, n);
}
}
/* /*
* Place a char array into a buffer * Place a char array into a buffer
*/ */
static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
{ {
if (b == NULL) { mav_array_memcpy(&buf[wire_offset], b, array_length);
memset(&buf[wire_offset], 0, array_length);
} else {
memcpy(&buf[wire_offset], b, array_length);
}
} }
/* /*
...@@ -171,11 +179,8 @@ static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const cha ...@@ -171,11 +179,8 @@ static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const cha
*/ */
static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
{ {
if (b == NULL) { mav_array_memcpy(&buf[wire_offset], b, array_length);
memset(&buf[wire_offset], 0, array_length);
} else {
memcpy(&buf[wire_offset], b, array_length);
}
} }
/* /*
...@@ -183,11 +188,8 @@ static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const ...@@ -183,11 +188,8 @@ static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const
*/ */
static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
{ {
if (b == NULL) { mav_array_memcpy(&buf[wire_offset], b, array_length);
memset(&buf[wire_offset], 0, array_length);
} else {
memcpy(&buf[wire_offset], b, array_length);
}
} }
#if MAVLINK_NEED_BYTE_SWAP #if MAVLINK_NEED_BYTE_SWAP
...@@ -207,11 +209,7 @@ static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, co ...@@ -207,11 +209,7 @@ static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, co
#define _MAV_PUT_ARRAY(TYPE, V) \ #define _MAV_PUT_ARRAY(TYPE, V) \
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
{ \ { \
if (b == NULL) { \ mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
} else { \
memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
} \
} }
#endif #endif
...@@ -224,9 +222,9 @@ _MAV_PUT_ARRAY(int64_t, i64) ...@@ -224,9 +222,9 @@ _MAV_PUT_ARRAY(int64_t, i64)
_MAV_PUT_ARRAY(float, f) _MAV_PUT_ARRAY(float, f)
_MAV_PUT_ARRAY(double, d) _MAV_PUT_ARRAY(double, d)
#define _MAV_RETURN_char(msg, wire_offset) _MAV_PAYLOAD(msg)[wire_offset] #define _MAV_RETURN_char(msg, wire_offset) (const char)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_int8_t(msg, wire_offset) (int8_t)_MAV_PAYLOAD(msg)[wire_offset] #define _MAV_RETURN_int8_t(msg, wire_offset) (const int8_t)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_uint8_t(msg, wire_offset) (uint8_t)_MAV_PAYLOAD(msg)[wire_offset] #define _MAV_RETURN_uint8_t(msg, wire_offset) (const uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
#if MAVLINK_NEED_BYTE_SWAP #if MAVLINK_NEED_BYTE_SWAP
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \ #define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
......
This diff is collapsed.
...@@ -11,16 +11,15 @@ ...@@ -11,16 +11,15 @@
<script type="text/javascript" src="https://www.google.com/jsapi?key=ABQIAAAA5Q6wxQ6lxKS8haLVdUJaqhSjosg_0jiTTs2iXtkDVG0n0If1mBRHzhWw5VqBZX-j4NuzoVpU-UaHVg"></script> <script type="text/javascript" src="https://www.google.com/jsapi?key=ABQIAAAA5Q6wxQ6lxKS8haLVdUJaqhSjosg_0jiTTs2iXtkDVG0n0If1mBRHzhWw5VqBZX-j4NuzoVpU-UaHVg"></script>
<script type="text/javascript"> <script type="text/javascript">
google.load("earth", "1", { 'language': 'en'}); google.load("earth", "1", { 'language': 'en'});
var ge = null; var ge = null;
var initialized = false; var initialized = false;
var currAircraft = 0; var currAircraft = 0;
var followEnabled = false; var followEnabled = false;
var lineAltitudeOffset = 0.5; ///< 0.5 m higher than waypoint, prevents the line from entering the ground var lineAltitudeOffset = 0.5; ///< 0.5 m higher than waypoint, prevents the line from entering the ground
var lastLat = 0; var lastLat = [];
var lastLon = 0; var lastLon = [];
var lastAlt = 0; var lastAlt = [];
var currLat = 47.3769; var currLat = 47.3769;
var currLon = 8.549444; var currLon = 8.549444;
var currAlt = 470; var currAlt = 470;
...@@ -59,6 +58,9 @@ var planeLoc; ...@@ -59,6 +58,9 @@ var planeLoc;
var aircraft = []; var aircraft = [];
var aircraftLocations = []; var aircraftLocations = [];
var aircraftLastLocations = []; var aircraftLastLocations = [];
var aircraftScaleFactors = [];
var aircraftLinks = [];
var aircraftModels = [];
var attitudes = []; var attitudes = [];
var locations = []; var locations = [];
var trails = []; var trails = [];
...@@ -104,7 +106,6 @@ var homePlacemark = null; ...@@ -104,7 +106,6 @@ var homePlacemark = null;
var heightMapPlacemark = null; var heightMapPlacemark = null;
var heightMapModel = null; var heightMapModel = null;
function getGlobal(variable) function getGlobal(variable)
{ {
return variable; return variable;
...@@ -303,7 +304,6 @@ function setGCSHome(lat, lon, alt) ...@@ -303,7 +304,6 @@ function setGCSHome(lat, lon, alt)
homeLon = lon; homeLon = lon;
homeAlt = alt; homeAlt = alt;
if (homePlacemark == null) if (homePlacemark == null)
{ {
var placemark = ge.createPlacemark(''); var placemark = ge.createPlacemark('');
...@@ -413,39 +413,39 @@ function updateWaypoint(id, index, lat, lon, alt, action) ...@@ -413,39 +413,39 @@ function updateWaypoint(id, index, lat, lon, alt, action)
function createAircraft(id, type, color) function createAircraft(id, type, color)
{ {
planePlacemark = ge.createPlacemark(''); aircraft[id] = ge.createPlacemark('');
planePlacemark.setName('aircraft'); aircraft[id].setName('aircraft');
planeModel = ge.createModel(''); aircraftModels[id] = ge.createModel('');
ge.getFeatures().appendChild(planePlacemark); ge.getFeatures().appendChild(aircraft[id]);
planeLoc = ge.createLocation(''); aircraftLocations[id] = ge.createLocation('');
planeModel.setLocation(planeLoc); aircraftModels[id].setLocation(aircraftLocations[id]);
planeLink = ge.createLink(''); aircraftLinks[id] = ge.createLink('');
planeOrient = ge.createOrientation(''); attitudes[id] = ge.createOrientation('');
planeModel.setOrientation(planeOrient); aircraftModels[id].setOrientation(attitudes[id]);
var factor = 1.0; aircraftScaleFactors[id] = 1.0;
//planeLink.setHref('http://www.asl.ethz.ch/people/rudink/senseSoarDummy.dae'); //planeLink.setHref('http://www.asl.ethz.ch/people/rudink/senseSoarDummy.dae');
planeLink.setHref('http://qgroundcontrol.org/_media/users/models/sfly-hex.dae'); aircraftLinks[id].setHref('http://qgroundcontrol.org/_media/users/models/sfly-hex.dae');
factor = 1.0/1000.0; aircraftScaleFactors[id] = 1.0/1000.0;
//planeLink.setHref('http://qgroundcontrol.org/_media/users/models/ascent-park-glider.dae'); //planeLink.setHref('http://qgroundcontrol.org/_media/users/models/ascent-park-glider.dae');
planeModel.setLink(planeLink); aircraftModels[id].setLink(aircraftLinks[id]);
var scale = planeModel.getScale(); var scale = aircraftModels[id].getScale();
scale.set(scale.getX()*factor, scale.getY()*factor, scale.getZ()*factor) scale.set(scale.getX()*aircraftScaleFactors[id], scale.getY()*aircraftScaleFactors[id], scale.getZ()*aircraftScaleFactors[id])
planeModel.setScale(scale); aircraftModels[id].setScale(scale);
planeModel.setAltitudeMode (ge.ALTITUDE_ABSOLUTE); aircraftModels[id].setAltitudeMode (ge.ALTITUDE_ABSOLUTE);
planeLoc.setLatitude(currLat); aircraftLocations[id].setLatitude(currLat);
planeLoc.setLongitude(currLon); aircraftLocations[id].setLongitude(currLon);
planeLoc.setAltitude(currAlt); aircraftLocations[id].setAltitude(currAlt);
planePlacemark.setGeometry(planeModel); aircraft[id].setGeometry(aircraftModels[id]);
// Write into global structure // Write into global structure
aircraft[id] = planePlacemark; aircraftLastLocations[id] = aircraftLocations[id];
attitudes[id] = planeOrient; lastLat[id] = 0;
aircraftLocations[id] = planeLoc; lastLon[id] = 0;
aircraftLastLocations[id] = ge.createLocation(''); lastAlt[id] = 0;
createTrail(id, color); createTrail(id, color);
createWaypointLine(id, color); createWaypointLine(id, color);
...@@ -565,13 +565,12 @@ function initCallback(object) ...@@ -565,13 +565,12 @@ function initCallback(object)
ge.getLayerRoot().enableLayerById(ge.LAYER_BORDERS, true); ge.getLayerRoot().enableLayerById(ge.LAYER_BORDERS, true);
ge.getLayerRoot().enableLayerById(ge.LAYER_TREES, true); ge.getLayerRoot().enableLayerById(ge.LAYER_TREES, true);
enableEventListener();
document.getElementById('JScript_initialized').setAttribute('value','true');
// Load heightmap // Load heightmap
// http://www.inf.ethz.ch/personal/lomeier/data/untex-environment.dae // http://www.inf.ethz.ch/personal/lomeier/data/untex-environment.dae
heightMapPlacemark = ge.createPlacemark(''); /*heightMapPlacemark = ge.createPlacemark('');
heightMapPlacemark.setName('aircraft'); heightMapPlacemark.setName('aircraft');
heightMapModel = ge.createModel(''); heightMapModel = ge.createModel('');
ge.getFeatures().appendChild(heightMapPlacemark); ge.getFeatures().appendChild(heightMapPlacemark);
...@@ -593,51 +592,56 @@ function initCallback(object) ...@@ -593,51 +592,56 @@ function initCallback(object)
planeLoc.setLongitude(currLon); planeLoc.setLongitude(currLon);
planeLoc.setAltitude(currAlt); planeLoc.setAltitude(currAlt);
heightMapPlacemark.setGeometry(heightMapModel); heightMapPlacemark.setGeometry(heightMapModel);*/
enableEventListener();
document.getElementById('JScript_initialized').setAttribute('value','true');
initialized = true; initialized = true;
} }
function setAircraftPositionAttitude(id, lat, lon, alt, roll, pitch, yaw) function setAircraftPositionAttitude(id, lat, lon, alt, roll, pitch, yaw)
{ {
if (lastLat[id] == 0)
{
lastLat[id] = lat;
lastLon[id] = lon;
}
if (id == currAircraft) if (id == currAircraft)
{ {
if (lastLat == 0) currFollowHeading = currFollowHeading*0.95+0.05*(((yaw/M_PI))*180.0);
{
lastLat = currLat;
lastLon = currLon;
}
currLat = lat; currLat = lat;
currLon = lon; currLon = lon;
var trueGroundAlt = ge.getGlobe().getGroundAltitude(lat, lon); var trueGroundAlt = ge.getGlobe().getGroundAltitude(lat, lon);
if (trueGroundAlt < alt) if (trueGroundAlt < alt)
{ {
currAlt = alt; currAlt = alt;
} }
else else
{ {
currAlt = trueGroundAlt+0.1; currAlt = trueGroundAlt+0.1;
} }
// Interpolate between t-1 and t and set new states }
lastLat = lastLat*0.5+currLat*0.5;
lastLon = lastLon*0.5+currLon*0.5; // Interpolate between t-1 and t and set new states
lastAlt = lastAlt*0.5+currAlt*0.5; //lastLat[id] = lastLat[id]*0.5+lat*0.5;
//lastLon[id] = lastLon[id]*0.5+lon*0.5;
//lastAlt[id] = lastAlt[id]*0.5+alt*0.5;
planeOrient.setRoll(+((roll/M_PI))*180.0); lastLat[id] = lastLat[id]*0.5+lat*0.5;
planeOrient.setTilt(-((pitch/M_PI))*180.0); lastLon[id] = lastLon[id]*0.5+lon*0.5;
planeOrient.setHeading(((yaw/M_PI))*180.0-90.0); lastAlt[id] = lastAlt[id]*0.5+alt*0.5;
planeModel.setOrientation(planeOrient);
currFollowHeading = currFollowHeading*0.95+0.05*(((yaw/M_PI))*180.0); attitudes[id].setRoll(+((roll/M_PI))*180.0);
attitudes[id].setTilt(-((pitch/M_PI))*180.0);
attitudes[id].setHeading(((yaw/M_PI))*180.0-90.0);
aircraftModels[id].setOrientation(attitudes[id]);
planeLoc.setLatitude(lastLat); aircraftLocations[id].setLatitude(lastLat[id]);
planeLoc.setLongitude(lastLon); aircraftLocations[id].setLongitude(lastLon[id]);
planeLoc.setAltitude(lastAlt); aircraftLocations[id].setAltitude(lastAlt[id]);
planeModel.setLocation(planeLoc); aircraftModels[id].setLocation(aircraftLocations[id]);
if (followEnabled) updateFollowAircraft(); if (followEnabled && id == currAircraft) updateFollowAircraft();
}
} }
function enableDaylight(enabled) function enableDaylight(enabled)
...@@ -703,16 +707,16 @@ function setViewMode(mode) ...@@ -703,16 +707,16 @@ function setViewMode(mode)
function updateFollowAircraft() function updateFollowAircraft()
{ {
currView = ge.getView().copyAsLookAt(ge.ALTITUDE_ABSOLUTE); currView = ge.getView().copyAsLookAt(ge.ALTITUDE_ABSOLUTE);
currView.setLatitude(lastLat); currView.setLatitude(lastLat[currAircraft]);
currView.setLongitude(lastLon); currView.setLongitude(lastLon[currAircraft]);
if (distanceMode == 1) if (distanceMode == 1)
{ {
var groundAltitude = ge.getGlobe().getGroundAltitude(lastLat, lastLon); var groundAltitude = ge.getGlobe().getGroundAltitude(lastLat[currAircraft], lastLon[currAircraft]);
currView.setAltitude(groundAltitude); currView.setAltitude(groundAltitude);
} }
if (distanceMode == 0) currView.setAltitude(lastAlt); if (distanceMode == 0) currView.setAltitude(lastAlt[currAircraft]);
currView.setRange(currViewRange); currView.setRange(currViewRange);
......
...@@ -545,19 +545,19 @@ TRANSLATIONS += es-MX.ts \ ...@@ -545,19 +545,19 @@ TRANSLATIONS += es-MX.ts \
# xbee support # xbee support
# libxbee only supported by linux and windows systems # libxbee only supported by linux and windows systems
#win32-msvc2008|win32-msvc2010|linux{ win32-msvc2008|win32-msvc2010|linux{
# HEADERS += src/comm/XbeeLinkInterface.h \ HEADERS += src/comm/XbeeLinkInterface.h \
# src/comm/XbeeLink.h \ src/comm/XbeeLink.h \
# src/comm/HexSpinBox.h \ src/comm/HexSpinBox.h \
# src/ui/XbeeConfigurationWindow.h \ src/ui/XbeeConfigurationWindow.h \
# src/comm/CallConv.h src/comm/CallConv.h
# SOURCES += src/comm/XbeeLink.cpp \ SOURCES += src/comm/XbeeLink.cpp \
# src/comm/HexSpinBox.cpp \ src/comm/HexSpinBox.cpp \
# src/ui/XbeeConfigurationWindow.cpp src/ui/XbeeConfigurationWindow.cpp
# DEFINES += XBEELINK DEFINES += XBEELINK
# INCLUDEPATH += thirdParty/libxbee INCLUDEPATH += thirdParty/libxbee
# TO DO: build library when it does not exists already # TO DO: build library when it does not exists already
# LIBS += -LthirdParty/libxbee/lib \ LIBS += -LthirdParty/libxbee/lib \
# -llibxbee -llibxbee
#
#} }
...@@ -204,8 +204,9 @@ QGCCore::~QGCCore() ...@@ -204,8 +204,9 @@ QGCCore::~QGCCore()
{ {
//mainWindow->storeSettings(); //mainWindow->storeSettings();
mainWindow->close(); mainWindow->close();
mainWindow->deleteLater(); //mainWindow->deleteLater();
// Delete singletons // Delete singletons
delete MainWindow::instance();
delete LinkManager::instance(); delete LinkManager::instance();
delete UASManager::instance(); delete UASManager::instance();
} }
......
...@@ -96,7 +96,7 @@ void MAVLinkXMLParserV10::processError(QProcess::ProcessError err) ...@@ -96,7 +96,7 @@ void MAVLinkXMLParserV10::processError(QProcess::ProcessError err)
bool MAVLinkXMLParserV10::generate() bool MAVLinkXMLParserV10::generate()
{ {
#ifdef Q_OS_WIN #ifdef Q_OS_WIN
QString generatorCall("%1/files/mavlink_generator/generator/mavgen.exe"); QString generatorCall("files/mavlink_generator/generator/mavgen.exe");
#endif #endif
#if (defined Q_OS_MAC) || (defined Q_OS_LINUX) #if (defined Q_OS_MAC) || (defined Q_OS_LINUX)
QString generatorCall("python"); QString generatorCall("python");
......
#include "HexSpinBox.h"
#include <qregexp.h>
HexSpinBox::HexSpinBox(QWidget *parent)
: QSpinBox(parent), validator(NULL)
{
setRange(0, 0x7fffffff);
validator = new QRegExpValidator(QRegExp("[0-9A-Fa-f]{1,8}"), this);
}
HexSpinBox::~HexSpinBox(void)
{
if(this->validator)
{
delete this->validator;
this->validator = NULL;
}
}
QValidator::State HexSpinBox::validate(QString &text, int &pos) const
{
return validator->validate(text, pos);
}
QString HexSpinBox::textFromValue(int value) const
{
return QString::number(value, 16).toUpper();
}
int HexSpinBox::valueFromText(const QString &text) const
{
bool ok;
return text.toInt(&ok, 16);
}
\ No newline at end of file
#ifndef HEXSPINBOX_H_
#define HEXSPINBOX_H_
#include <qspinbox.h>
class QRegExpValidator;
class HexSpinBox : public QSpinBox
{
Q_OBJECT
public:
HexSpinBox(QWidget *parent = 0);
~HexSpinBox(void);
protected:
QValidator::State validate(QString &text, int &pos) const;
int valueFromText(const QString &text) const;
QString textFromValue(int value) const;
private:
QRegExpValidator *validator;
};
#endif // HEXSPINBOX_H_
...@@ -358,19 +358,19 @@ void MAVLinkSimulationLink::mainloop() ...@@ -358,19 +358,19 @@ void MAVLinkSimulationLink::mainloop()
if (rate10hzCounter == 1000 / rate / 9) { if (rate10hzCounter == 1000 / rate / 9) {
rate10hzCounter = 1; rate10hzCounter = 1;
float lastX = x; double lastX = x;
float lastY = y; double lastY = y;
float lastZ = z; double lastZ = z;
float hackDt = 0.1f; // 100 ms double hackDt = 0.1f; // 100 ms
// Move X Position // Move X Position
x = 12.0*sin(((double)circleCounter)/200.0); x = 12.0*sin(((double)circleCounter)/200.0);
y = 5.0*cos(((double)circleCounter)/200.0); y = 5.0*cos(((double)circleCounter)/200.0);
z = 1.8 + 1.2*sin(((double)circleCounter)/200.0); z = 1.8 + 1.2*sin(((double)circleCounter)/200.0);
float xSpeed = (x - lastX)/hackDt; double xSpeed = (x - lastX)/hackDt;
float ySpeed = (y - lastY)/hackDt; double ySpeed = (y - lastY)/hackDt;
float zSpeed = (z - lastZ)/hackDt; double zSpeed = (z - lastZ)/hackDt;
...@@ -414,12 +414,12 @@ void MAVLinkSimulationLink::mainloop() ...@@ -414,12 +414,12 @@ void MAVLinkSimulationLink::mainloop()
memcpy(stream+streampointer,buffer, bufferlength); memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength; streampointer += bufferlength;
// // GLOBAL POSITION VEHICLE 2 // 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, xSpeed, ySpeed, zSpeed); mavlink_msg_global_position_int_pack(systemId+1, componentId+1, &ret, 0, (473780.28137103+(x+0.00001))*1E3, (85489.9892510421+((y/2)+0.00001))*1E3, (z+550.0)*1000.0, (z+550.0)*1000.0-1, xSpeed, ySpeed, zSpeed, yaw);
// bufferlength = mavlink_msg_to_send_buffer(buffer, &ret); bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
// //add data into datastream //add data into datastream
// memcpy(stream+streampointer,buffer, bufferlength); memcpy(stream+streampointer,buffer, bufferlength);
// streampointer += bufferlength; streampointer += bufferlength;
// // ATTITUDE VEHICLE 2 // // ATTITUDE VEHICLE 2
// mavlink_msg_attitude_pack(54, MAV_COMP_ID_IMU, &ret, 0, 0, 0, atan2((y/2)+0.3, (x+0.002)), 0, 0, 0); // mavlink_msg_attitude_pack(54, MAV_COMP_ID_IMU, &ret, 0, 0, 0, atan2((y/2)+0.3, (x+0.002)), 0, 0, 0);
...@@ -427,7 +427,7 @@ void MAVLinkSimulationLink::mainloop() ...@@ -427,7 +427,7 @@ void MAVLinkSimulationLink::mainloop()
// // GLOBAL POSITION VEHICLE 3 // // GLOBAL POSITION VEHICLE 3
// mavlink_msg_global_position_int_pack(60, componentId, &ret, (473780.28137103+(x/2+0.002))*1E3, (85489.9892510421+((y*2)+0.3))*1E3, (z+590.0)*1000.0, 0*100.0, 0*100.0, 0*100.0); // mavlink_msg_global_position_int_pack(60, componentId, &ret, 0, (473780.28137103+(x/2+0.002))*1E3, (85489.9892510421+((y*2)+0.3))*1E3, (z+590.0)*1000.0, 0*100.0, 0*100.0, 0*100.0);
// bufferlength = mavlink_msg_to_send_buffer(buffer, &ret); // bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
// //add data into datastream // //add data into datastream
// memcpy(stream+streampointer,buffer, bufferlength); // memcpy(stream+streampointer,buffer, bufferlength);
...@@ -565,6 +565,15 @@ void MAVLinkSimulationLink::mainloop() ...@@ -565,6 +565,15 @@ void MAVLinkSimulationLink::mainloop()
memcpy(stream+streampointer,buffer, bufferlength); memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength; streampointer += bufferlength;
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_heartbeat_pack(systemId+1, componentId+1, &msg, mavType, MAV_AUTOPILOT_GENERIC, system.base_mode, system.custom_mode, system.system_status);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// Send controller states // Send controller states
......
...@@ -227,23 +227,25 @@ namespace core { ...@@ -227,23 +227,25 @@ namespace core {
#endif //DEBUG_PUREIMAGECACHE #endif //DEBUG_PUREIMAGECACHE
QString db=dir+"Data.qmdb"; QString db=dir+"Data.qmdb";
QSqlDatabase cn; {
QSqlDatabase cn;
cn = QSqlDatabase::addDatabase("QSQLITE",QString::number(id));
cn = QSqlDatabase::addDatabase("QSQLITE",QString::number(id));
cn.setDatabaseName(db); cn.setDatabaseName(db);
cn.setConnectOptions("QSQLITE_ENABLE_SHARED_CACHE"); cn.setConnectOptions("QSQLITE_ENABLE_SHARED_CACHE");
if(cn.open()) if(cn.open())
{
QSqlQuery query(cn);
query.exec(QString("SELECT Tile FROM TilesData WHERE id = (SELECT id FROM Tiles WHERE X=%1 AND Y=%2 AND Zoom=%3 AND Type=%4)").arg(pos.X()).arg(pos.Y()).arg(zoom).arg((int) type));
query.next();
if(query.isValid())
{ {
ar=query.value(0).toByteArray(); QSqlQuery query(cn);
} query.exec(QString("SELECT Tile FROM TilesData WHERE id = (SELECT id FROM Tiles WHERE X=%1 AND Y=%2 AND Zoom=%3 AND Type=%4)").arg(pos.X()).arg(pos.Y()).arg(zoom).arg((int) type));
cn.close(); query.next();
} if(query.isValid())
{
ar=query.value(0).toByteArray();
}
cn.close();
}
}
QSqlDatabase::removeDatabase(QString::number(id)); QSqlDatabase::removeDatabase(QString::number(id));
lock.unlock(); lock.unlock();
return ar; return ar;
......
...@@ -82,6 +82,12 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), ...@@ -82,6 +82,12 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
isGlobalPositionKnown(false), isGlobalPositionKnown(false),
systemIsArmed(false) systemIsArmed(false)
{ {
for (unsigned int i = 0; i<255;++i)
{
componentID[i] = -1;
componentMulti[i] = false;
}
color = UASInterface::getNextColor(); color = UASInterface::getNextColor();
setBatterySpecs(QString("9V,9.5V,12.6V")); setBatterySpecs(QString("9V,9.5V,12.6V"));
connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState())); connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
...@@ -210,6 +216,27 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -210,6 +216,27 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
QString uasState; QString uasState;
QString stateDescription; QString stateDescription;
bool multiComponentSourceDetected = false;
bool wrongComponent = false;
// Store component ID
if (componentID[message.msgid] == -1)
{
componentID[message.msgid] = message.compid;
}
else
{
// Got this message already
if (componentID[message.msgid] != message.compid)
{
componentMulti[message.msgid] = true;
wrongComponent = true;
}
}
if (componentMulti[message.msgid] == true) multiComponentSourceDetected = true;
switch (message.msgid) switch (message.msgid)
{ {
case MAVLINK_MSG_ID_HEARTBEAT: case MAVLINK_MSG_ID_HEARTBEAT:
...@@ -336,6 +363,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -336,6 +363,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
break; break;
case MAVLINK_MSG_ID_SYS_STATUS: case MAVLINK_MSG_ID_SYS_STATUS:
{ {
if (multiComponentSourceDetected && message.compid != MAV_COMP_ID_IMU_2)
{
break;
}
mavlink_sys_status_t state; mavlink_sys_status_t state;
mavlink_msg_sys_status_decode(&message, &state); mavlink_msg_sys_status_decode(&message, &state);
...@@ -371,6 +402,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -371,6 +402,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
break; break;
case MAVLINK_MSG_ID_ATTITUDE: case MAVLINK_MSG_ID_ATTITUDE:
{ {
if (wrongComponent) break;
mavlink_attitude_t attitude; mavlink_attitude_t attitude;
mavlink_msg_attitude_decode(&message, &attitude); mavlink_msg_attitude_decode(&message, &attitude);
quint64 time = getUnixReferenceTime(attitude.time_boot_ms); quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
...@@ -499,7 +532,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -499,7 +532,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if (!isnan(alt) && !isinf(alt)) if (!isnan(alt) && !isinf(alt))
{ {
alt = 0; alt = 0;
emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE"); //emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE");
} }
// FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time); // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
// Smaller than threshold and not NaN // Smaller than threshold and not NaN
......
...@@ -544,6 +544,8 @@ protected: ...@@ -544,6 +544,8 @@ protected:
quint64 getUnixTimeFromMs(quint64 time); quint64 getUnixTimeFromMs(quint64 time);
/** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */ /** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
quint64 getUnixReferenceTime(quint64 time); quint64 getUnixReferenceTime(quint64 time);
int componentID[256];
bool componentMulti[256];
protected slots: protected slots:
/** @brief Write settings to disk */ /** @brief Write settings to disk */
......
...@@ -50,8 +50,8 @@ HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) : ...@@ -50,8 +50,8 @@ HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) :
acceptUnitList(new QStringList()), acceptUnitList(new QStringList()),
lastPaintTime(0), lastPaintTime(0),
columns(3), columns(3),
valuesChanged(true)/*, valuesChanged(true),
m_ui(new Ui::HDDisplay)*/ m_ui(NULL)
{ {
setWindowTitle(title); setWindowTitle(title);
//m_ui->setupUi(this); //m_ui->setupUi(this);
...@@ -135,7 +135,22 @@ HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) : ...@@ -135,7 +135,22 @@ HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) :
HDDisplay::~HDDisplay() HDDisplay::~HDDisplay()
{ {
saveState(); saveState();
delete m_ui; if(this->refreshTimer)
{
delete this->refreshTimer;
}
if(this->acceptList)
{
delete this->acceptList;
}
if(this->acceptUnitList)
{
delete this->acceptUnitList;
}
if(this->m_ui)
{
delete m_ui;
}
} }
QSize HDDisplay::sizeHint() const QSize HDDisplay::sizeHint() const
......
...@@ -136,6 +136,11 @@ HSIDisplay::HSIDisplay(QWidget *parent) : ...@@ -136,6 +136,11 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
setFocusPolicy(Qt::StrongFocus); setFocusPolicy(Qt::StrongFocus);
} }
HSIDisplay::~HSIDisplay()
{
}
void HSIDisplay::resetMAVState() void HSIDisplay::resetMAVState()
{ {
mavInitialized = false; mavInitialized = false;
......
...@@ -48,7 +48,7 @@ class HSIDisplay : public HDDisplay ...@@ -48,7 +48,7 @@ class HSIDisplay : public HDDisplay
Q_OBJECT Q_OBJECT
public: public:
HSIDisplay(QWidget *parent = 0); HSIDisplay(QWidget *parent = 0);
// ~HSIDisplay(); ~HSIDisplay();
public slots: public slots:
void setActiveUAS(UASInterface* uas); void setActiveUAS(UASInterface* uas);
......
...@@ -7,6 +7,11 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) : ...@@ -7,6 +7,11 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
mavlink_message_info_t msg[256] = MAVLINK_MESSAGE_INFO; mavlink_message_info_t msg[256] = MAVLINK_MESSAGE_INFO;
memcpy(messageInfo, msg, sizeof(mavlink_message_info_t)*256); memcpy(messageInfo, msg, sizeof(mavlink_message_info_t)*256);
memset(receivedMessages, 0, sizeof(mavlink_message_t)*256); memset(receivedMessages, 0, sizeof(mavlink_message_t)*256);
for (unsigned int i = 0; i<255;++i)
{
componentID[i] = -1;
componentMulti[i] = false;
}
// Fill filter // Fill filter
messageFilter.insert(MAVLINK_MSG_ID_HEARTBEAT, false); messageFilter.insert(MAVLINK_MSG_ID_HEARTBEAT, false);
...@@ -69,6 +74,26 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag ...@@ -69,6 +74,26 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 time) void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 time)
{ {
bool multiComponentSourceDetected = false;
bool wrongComponent = false;
// Store component ID
if (componentID[msg->msgid] == -1)
{
componentID[msg->msgid] = msg->compid;
}
else
{
// Got this message already
if (componentID[msg->msgid] != msg->compid)
{
componentMulti[msg->msgid] = true;
wrongComponent = true;
}
}
if (componentMulti[msg->msgid] == true) multiComponentSourceDetected = true;
// Add field tree widget item // Add field tree widget item
uint8_t msgid = msg->msgid; uint8_t msgid = msg->msgid;
if (messageFilter.contains(msgid)) return; if (messageFilter.contains(msgid)) return;
...@@ -78,6 +103,8 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 ...@@ -78,6 +103,8 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
QString name("%1.%2"); QString name("%1.%2");
QString unit(""); QString unit("");
name = name.arg(messageInfo[msgid].name, fieldName); name = name.arg(messageInfo[msgid].name, fieldName);
if (multiComponentSourceDetected) name.prepend(QString("C%1:").arg(msg->compid));
name.prepend(QString("M%1:").arg(msg->sysid));
switch (messageInfo[msgid].fields[fieldid].type) switch (messageInfo[msgid].fields[fieldid].type)
{ {
case MAVLINK_TYPE_CHAR: case MAVLINK_TYPE_CHAR:
......
...@@ -30,6 +30,8 @@ protected: ...@@ -30,6 +30,8 @@ protected:
mavlink_message_info_t messageInfo[256]; ///< Message information mavlink_message_info_t messageInfo[256]; ///< Message information
QMap<uint16_t, bool> messageFilter; ///< Message/field names not to emit QMap<uint16_t, bool> messageFilter; ///< Message/field names not to emit
QMap<uint16_t, bool> textMessageFilter; ///< Message/field names not to emit in text mode QMap<uint16_t, bool> textMessageFilter; ///< Message/field names not to emit in text mode
int componentID[256]; ///< Multi component detection
bool componentMulti[256]; ///< Multi components detected
}; };
......
...@@ -91,7 +91,7 @@ MainWindow::MainWindow(QWidget *parent): ...@@ -91,7 +91,7 @@ MainWindow::MainWindow(QWidget *parent):
currentStyle(QGC_MAINWINDOW_STYLE_INDOOR), currentStyle(QGC_MAINWINDOW_STYLE_INDOOR),
aboutToCloseFlag(false), aboutToCloseFlag(false),
changingViewsFlag(false), changingViewsFlag(false),
centerStackActionGroup(this), centerStackActionGroup(new QActionGroup(this)),
styleFileName(QCoreApplication::applicationDirPath() + "/style-indoor.css"), styleFileName(QCoreApplication::applicationDirPath() + "/style-indoor.css"),
autoReconnect(false), autoReconnect(false),
lowPowerMode(false) lowPowerMode(false)
...@@ -138,7 +138,7 @@ MainWindow::MainWindow(QWidget *parent): ...@@ -138,7 +138,7 @@ MainWindow::MainWindow(QWidget *parent):
setCorner(Qt::BottomRightCorner, Qt::RightDockWidgetArea); setCorner(Qt::BottomRightCorner, Qt::RightDockWidgetArea);
// Setup UI state machines // Setup UI state machines
centerStackActionGroup.setExclusive(true); centerStackActionGroup->setExclusive(true);
centerStack = new QStackedWidget(this); centerStack = new QStackedWidget(this);
setCentralWidget(centerStack); setCentralWidget(centerStack);
...@@ -246,8 +246,8 @@ MainWindow::~MainWindow() ...@@ -246,8 +246,8 @@ MainWindow::~MainWindow()
if (dockWidget) if (dockWidget)
{ {
// Remove dock widget from main window // Remove dock widget from main window
removeDockWidget(dockWidget); // removeDockWidget(dockWidget);
delete dockWidget->widget(); // delete dockWidget->widget();
delete dockWidget; delete dockWidget;
} }
else else
...@@ -417,14 +417,14 @@ void MainWindow::buildCommonWidgets() ...@@ -417,14 +417,14 @@ void MainWindow::buildCommonWidgets()
parametersDockWidget->setObjectName("PARAMETER_INTERFACE_DOCKWIDGET"); parametersDockWidget->setObjectName("PARAMETER_INTERFACE_DOCKWIDGET");
addTool(parametersDockWidget, tr("Calibration and Parameters"), Qt::RightDockWidgetArea); addTool(parametersDockWidget, tr("Calibration and Parameters"), Qt::RightDockWidgetArea);
} }
if (!hsiDockWidget) { if (!hsiDockWidget) {
hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this); hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
hsiDockWidget->setWidget( new HSIDisplay(this) ); hsiDockWidget->setWidget( new HSIDisplay(this) );
hsiDockWidget->setObjectName("HORIZONTAL_SITUATION_INDICATOR_DOCK_WIDGET"); hsiDockWidget->setObjectName("HORIZONTAL_SITUATION_INDICATOR_DOCK_WIDGET");
addTool(hsiDockWidget, tr("Horizontal Situation"), Qt::BottomDockWidgetArea); addTool(hsiDockWidget, tr("Horizontal Situation"), Qt::BottomDockWidgetArea);
} }
if (!headDown1DockWidget) { if (!headDown1DockWidget) {
headDown1DockWidget = new QDockWidget(tr("Flight Display"), this); headDown1DockWidget = new QDockWidget(tr("Flight Display"), this);
HDDisplay* hdDisplay = new HDDisplay(acceptList, "Flight Display", this); HDDisplay* hdDisplay = new HDDisplay(acceptList, "Flight Display", this);
...@@ -442,7 +442,7 @@ void MainWindow::buildCommonWidgets() ...@@ -442,7 +442,7 @@ void MainWindow::buildCommonWidgets()
headDown2DockWidget->setObjectName("HEAD_DOWN_DISPLAY_2_DOCK_WIDGET"); headDown2DockWidget->setObjectName("HEAD_DOWN_DISPLAY_2_DOCK_WIDGET");
addTool(headDown2DockWidget, tr("Actuator Status"), Qt::RightDockWidgetArea); addTool(headDown2DockWidget, tr("Actuator Status"), Qt::RightDockWidgetArea);
} }
if (!rcViewDockWidget) { if (!rcViewDockWidget) {
rcViewDockWidget = new QDockWidget(tr("Radio Control"), this); rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
rcViewDockWidget->setWidget( new QGCRemoteControlView(this) ); rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
...@@ -555,7 +555,7 @@ void MainWindow::addCentralWidget(QWidget* widget, const QString& title) ...@@ -555,7 +555,7 @@ void MainWindow::addCentralWidget(QWidget* widget, const QString& title)
QVariant var; QVariant var;
var.setValue((QWidget*)widget); var.setValue((QWidget*)widget);
tempAction->setData(var); tempAction->setData(var);
centerStackActionGroup.addAction(tempAction); centerStackActionGroup->addAction(tempAction);
connect(tempAction,SIGNAL(triggered()),this, SLOT(showCentralWidget())); connect(tempAction,SIGNAL(triggered()),this, SLOT(showCentralWidget()));
connect(widget, SIGNAL(visibilityChanged(bool)), tempAction, SLOT(setChecked(bool))); connect(widget, SIGNAL(visibilityChanged(bool)), tempAction, SLOT(setChecked(bool)));
tempAction->setChecked(widget->isVisible()); tempAction->setChecked(widget->isVisible());
...@@ -1503,108 +1503,3 @@ QList<QAction*> MainWindow::listLinkMenuActions(void) ...@@ -1503,108 +1503,3 @@ QList<QAction*> MainWindow::listLinkMenuActions(void)
{ {
return ui.menuNetwork->actions(); return ui.menuNetwork->actions();
} }
/*
void MainWindow::buildSenseSoarWidgets()
{
if (!linechartWidget)
{
// Center widgets
linechartWidget = new Linecharts(this);
addToCentralWidgetsMenu(linechartWidget, tr("Realtime Plot"), SLOT(showCentralWidget()), CENTRAL_LINECHART);
}
if (!hudWidget)
{
hudWidget = new HUD(320, 240, this);
addToCentralWidgetsMenu(hudWidget, tr("Head Up Display"), SLOT(showCentralWidget()), CENTRAL_HUD);
}
if (!dataplotWidget) {
dataplotWidget = new QGCDataPlot2D(this);
addToCentralWidgetsMenu(dataplotWidget, "Logfile Plot", SLOT(showCentralWidget()), CENTRAL_DATA_PLOT);
}
#ifdef QGC_OSG_ENABLED
if (!_3DWidget) {
_3DWidget = Q3DWidgetFactory::get("PIXHAWK");
addToCentralWidgetsMenu(_3DWidget, tr("Local 3D"), SLOT(showCentralWidget()), CENTRAL_3D_LOCAL);
}
#endif
#ifdef QGC_OSGEARTH_ENABLED
if (!_3DMapWidget) {
_3DMapWidget = Q3DWidgetFactory::get("MAP3D");
addToCentralWidgetsMenu(_3DMapWidget, tr("OSG Earth 3D"), SLOT(showCentralWidget()), CENTRAL_OSGEARTH);
}
#endif
#if (defined _MSC_VER) | (defined Q_OS_MAC)
if (!gEarthWidget) {
gEarthWidget = new QGCGoogleEarthView(this);
addToCentralWidgetsMenu(gEarthWidget, tr("Google Earth"), SLOT(showCentralWidget()), CENTRAL_GOOGLE_EARTH);
}
#endif
// Dock widgets
if (!parametersDockWidget) {
parametersDockWidget = new QDockWidget(tr("Calibration and Onboard Parameters"), this);
parametersDockWidget->setWidget( new ParameterInterface(this) );
parametersDockWidget->setObjectName("PARAMETER_INTERFACE_DOCKWIDGET");
addToToolsMenu (parametersDockWidget, tr("Calibration and Parameters"), SLOT(showToolWidget(bool)), MENU_PARAMETERS, Qt::RightDockWidgetArea);
}
if (!hsiDockWidget) {
hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
hsiDockWidget->setWidget( new HSIDisplay(this) );
hsiDockWidget->setObjectName("HORIZONTAL_SITUATION_INDICATOR_DOCK_WIDGET");
addToToolsMenu (hsiDockWidget, tr("Horizontal Situation"), SLOT(showToolWidget(bool)), MENU_HSI, Qt::BottomDockWidgetArea);
}
if (!rcViewDockWidget) {
rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
rcViewDockWidget->setObjectName("RADIO_CONTROL_CHANNELS_DOCK_WIDGET");
addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget(bool)), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
}
if (!headUpDockWidget) {
headUpDockWidget = new QDockWidget(tr("HUD"), this);
headUpDockWidget->setWidget( new HUD(320, 240, this));
headUpDockWidget->setObjectName("HEAD_UP_DISPLAY_DOCK_WIDGET");
addToToolsMenu (headUpDockWidget, tr("Head Up Display"), SLOT(showToolWidget(bool)), MENU_HUD, Qt::RightDockWidgetArea);
}
}
void MainWindow::connectSenseSoarWidgets()
{
}
void MainWindow::arrangeSenseSoarCenterStack()
{
if (!centerStack) {
qDebug() << "Center Stack not Created!";
return;
}
if (linechartWidget && (centerStack->indexOf(linechartWidget) == -1)) centerStack->addWidget(linechartWidget);
#ifdef QGC_OSG_ENABLED
if (_3DWidget && (centerStack->indexOf(_3DWidget) == -1)) centerStack->addWidget(_3DWidget);
#endif
#ifdef QGC_OSGEARTH_ENABLED
if (_3DMapWidget && (centerStack->indexOf(_3DMapWidget) == -1)) centerStack->addWidget(_3DMapWidget);
#endif
#if (defined _MSC_VER) | (defined Q_OS_MAC)
if (gEarthWidget && (centerStack->indexOf(gEarthWidget) == -1)) centerStack->addWidget(gEarthWidget);
#endif
if (hudWidget && (centerStack->indexOf(hudWidget) == -1)) centerStack->addWidget(hudWidget);
if (dataplotWidget && (centerStack->indexOf(dataplotWidget) == -1)) centerStack->addWidget(dataplotWidget);
}
void MainWindow::connectSenseSoarActions()
{
}
*/
...@@ -303,7 +303,7 @@ protected: ...@@ -303,7 +303,7 @@ protected:
QSettings settings; QSettings settings;
QStackedWidget *centerStack; QStackedWidget *centerStack;
QActionGroup centerStackActionGroup; QActionGroup* centerStackActionGroup;
// Center widgets // Center widgets
QPointer<Linecharts> linechartWidget; QPointer<Linecharts> linechartWidget;
......
...@@ -82,7 +82,7 @@ void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t m ...@@ -82,7 +82,7 @@ void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t m
{ {
msgHz = 1; msgHz = 1;
} }
float newHz = 0.001f*msgHz+0.999f*messagesHz.value(message.msgid, 1); float newHz = 0.05f*msgHz+0.95f*messagesHz.value(message.msgid, 1);
messagesHz.insert(message.msgid, newHz); messagesHz.insert(message.msgid, newHz);
} }
......
...@@ -43,8 +43,8 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) : ...@@ -43,8 +43,8 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) :
uasId(-1), uasId(-1),
rssi(0.0f), rssi(0.0f),
updated(false), updated(false),
channelLayout(new QVBoxLayout())//, channelLayout(new QVBoxLayout()),
//ui(new Ui::QGCRemoteControlView) ui(NULL)
{ {
ui->setupUi(this); ui->setupUi(this);
QGridLayout* layout = new QGridLayout(this); QGridLayout* layout = new QGridLayout(this);
...@@ -71,8 +71,14 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) : ...@@ -71,8 +71,14 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) :
QGCRemoteControlView::~QGCRemoteControlView() QGCRemoteControlView::~QGCRemoteControlView()
{ {
delete ui; if(this->ui)
delete channelLayout; {
delete ui;
}
if(this->channelLayout)
{
delete channelLayout;
}
} }
void QGCRemoteControlView::setUASId(int id) void QGCRemoteControlView::setUASId(int id)
...@@ -172,7 +178,7 @@ void QGCRemoteControlView::setRemoteRSSI(float rssiNormalized) ...@@ -172,7 +178,7 @@ void QGCRemoteControlView::setRemoteRSSI(float rssiNormalized)
void QGCRemoteControlView::appendChannelWidget(int channelId) void QGCRemoteControlView::appendChannelWidget(int channelId)
{ {
// Create new layout // Create new layout
QHBoxLayout* layout = new QHBoxLayout(); QHBoxLayout* layout = new QHBoxLayout(this);
// Add content // Add content
layout->addWidget(new QLabel(QString("Channel %1").arg(channelId + 1), this)); layout->addWidget(new QLabel(QString("Channel %1").arg(channelId + 1), this));
QLabel* raw = new QLabel(this); QLabel* raw = new QLabel(this);
......
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