Commit ff8e1e4f authored by Lorenz Meier's avatar Lorenz Meier

Minor tweaks and improvements

parent e1b1557e
...@@ -184,13 +184,14 @@ QDoubleSpinBox::down-button { ...@@ -184,13 +184,14 @@ QDoubleSpinBox::down-button {
} }
QPushButton { QPushButton {
font-weight: bold; /*font-weight: bold;
min-height: 18px; min-height: 18px;
max-height: 18px; max-height: 18px;
min-width: 60px;*/
border: 2px solid #4A4A4F; border: 2px solid #4A4A4F;
border-radius: 5px; border-radius: 3px;
padding-left: 5px; padding-left: 8px;
padding-right: 5px; padding-right: 8px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #232228, stop: 1 #020208); background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #232228, stop: 1 #020208);
} }
...@@ -206,11 +207,11 @@ QPushButton:pressed { ...@@ -206,11 +207,11 @@ QPushButton:pressed {
QToolButton { QToolButton {
font-weight: bold; font-weight: bold;
min-height: 16px; min-height: 18px;
min-width: 24px; min-width: 24px;
max-height: 18px; max-height: 18px;
border: 2px solid #4A4A4F; border: 2px solid #4A4A4F;
border-radius: 5px; border-radius: 3px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #232228, stop: 1 #020208); background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #232228, stop: 1 #020208);
} }
......
...@@ -743,7 +743,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -743,7 +743,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_param_value_t value; mavlink_param_value_t value;
mavlink_msg_param_value_decode(&message, &value); mavlink_msg_param_value_decode(&message, &value);
QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
QString parameterName = QString(bytes); // Construct a string stopping at the first NUL (0) character, else copy the whole
// byte array (max MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN, so safe)
QString parameterName(bytes);
int component = message.compid; int component = message.compid;
mavlink_param_union_t val; mavlink_param_union_t val;
val.param_float = value.param_value; val.param_float = value.param_value;
......
...@@ -28,8 +28,10 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) : ...@@ -28,8 +28,10 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
messageFilter.insert(MAVLINK_MSG_ID_MISSION_COUNT, false); messageFilter.insert(MAVLINK_MSG_ID_MISSION_COUNT, false);
messageFilter.insert(MAVLINK_MSG_ID_MISSION_ACK, false); messageFilter.insert(MAVLINK_MSG_ID_MISSION_ACK, false);
messageFilter.insert(MAVLINK_MSG_ID_DATA_STREAM, false); messageFilter.insert(MAVLINK_MSG_ID_DATA_STREAM, false);
#ifdef MAVLINK_ENABLED_PIXHAWK #ifdef MAVLINK_MSG_ID_ENCAPSULATED_DATA
messageFilter.insert(MAVLINK_MSG_ID_ENCAPSULATED_DATA, false); messageFilter.insert(MAVLINK_MSG_ID_ENCAPSULATED_DATA, false);
#endif
#ifdef MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE
messageFilter.insert(MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, false); messageFilter.insert(MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, false);
#endif #endif
messageFilter.insert(MAVLINK_MSG_ID_EXTENDED_MESSAGE, false); messageFilter.insert(MAVLINK_MSG_ID_EXTENDED_MESSAGE, 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