Commit 4776d22d authored by Don Gagne's avatar Don Gagne

Merge pull request #3227 from NaterGator/hilfix

Fix HIL mode not being properly detected for #3226
parents 3ae7cbb2 861a2d07
...@@ -494,6 +494,8 @@ public: ...@@ -494,6 +494,8 @@ public:
uint messagesLost () { return _messagesLost; } uint messagesLost () { return _messagesLost; }
bool flying () const { return _flying; } bool flying () const { return _flying; }
bool guidedMode () const; bool guidedMode () const;
uint8_t baseMode () const { return _base_mode; }
uint32_t customMode () const { return _custom_mode; }
Fact* roll (void) { return &_rollFact; } Fact* roll (void) { return &_rollFact; }
Fact* heading (void) { return &_headingFact; } Fact* heading (void) { return &_headingFact; }
......
...@@ -58,8 +58,6 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi ...@@ -58,8 +58,6 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi
receiveDropRate(0), receiveDropRate(0),
sendDropRate(0), sendDropRate(0),
base_mode(0),
custom_mode(0),
status(-1), status(-1),
startTime(QGC::groundTimeMilliseconds()), startTime(QGC::groundTimeMilliseconds()),
...@@ -1440,6 +1438,7 @@ void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll ...@@ -1440,6 +1438,7 @@ void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll
if (!_vehicle) { if (!_vehicle) {
return; return;
} }
const uint8_t base_mode = _vehicle->baseMode();
// If system has manual inputs enabled and is armed // If system has manual inputs enabled and is armed
if(((base_mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (base_mode & MAV_MODE_FLAG_HIL_ENABLED)) if(((base_mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (base_mode & MAV_MODE_FLAG_HIL_ENABLED))
...@@ -1686,7 +1685,7 @@ void UAS::sendHilState(quint64 time_us, float roll, float pitch, float yaw, floa ...@@ -1686,7 +1685,7 @@ void UAS::sendHilState(quint64 time_us, float roll, float pitch, float yaw, floa
return; return;
} }
if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED) if (_vehicle->hilMode())
{ {
float q[4]; float q[4];
...@@ -1766,7 +1765,7 @@ void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, fl ...@@ -1766,7 +1765,7 @@ void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, fl
return; return;
} }
if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED) if (_vehicle->hilMode())
{ {
float xacc_corrupt = addZeroMeanNoise(xacc, xacc_var); float xacc_corrupt = addZeroMeanNoise(xacc, xacc_var);
float yacc_corrupt = addZeroMeanNoise(yacc, yacc_var); float yacc_corrupt = addZeroMeanNoise(yacc, yacc_var);
...@@ -1817,7 +1816,7 @@ void UAS::sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, floa ...@@ -1817,7 +1816,7 @@ void UAS::sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, floa
Q_UNUSED(quality); Q_UNUSED(quality);
Q_UNUSED(ground_distance); Q_UNUSED(ground_distance);
if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED) if (_vehicle->hilMode())
{ {
#if 0 #if 0
mavlink_message_t msg; mavlink_message_t msg;
...@@ -1849,7 +1848,7 @@ void UAS::sendHilGps(quint64 time_us, double lat, double lon, double alt, int fi ...@@ -1849,7 +1848,7 @@ void UAS::sendHilGps(quint64 time_us, double lat, double lon, double alt, int fi
if (QGC::groundTimeMilliseconds() - lastSendTimeGPS < 100) if (QGC::groundTimeMilliseconds() - lastSendTimeGPS < 100)
return; return;
if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED) if (_vehicle->hilMode())
{ {
float course = cog; float course = cog;
// map to 0..2pi // map to 0..2pi
......
...@@ -370,8 +370,6 @@ protected: //COMMENTS FOR TEST UNIT ...@@ -370,8 +370,6 @@ protected: //COMMENTS FOR TEST UNIT
float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS
/// BASIC UAS TYPE, NAME AND STATE /// BASIC UAS TYPE, NAME AND STATE
uint8_t base_mode; ///< The current mode of the MAV
uint32_t custom_mode; ///< The current mode of the MAV
int status; ///< The current status of the MAV int status; ///< The current status of the MAV
/// TIMEKEEPING /// TIMEKEEPING
......
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