forked from Archive/PX4-Autopilot
Merge branch 'master' into rc_timeout
This commit is contained in:
commit
605d7277d8
|
@ -389,18 +389,22 @@ class uploader(object):
|
|||
self.otp_pid = self.otp[12:8:-1]
|
||||
self.otp_coa = self.otp[32:160]
|
||||
# show user:
|
||||
print("type: " + self.otp_id.decode('Latin-1'))
|
||||
print("idtype: " + binascii.b2a_qp(self.otp_idtype).decode('Latin-1'))
|
||||
print("vid: " + binascii.hexlify(self.otp_vid).decode('Latin-1'))
|
||||
print("pid: "+ binascii.hexlify(self.otp_pid).decode('Latin-1'))
|
||||
print("coa: "+ binascii.b2a_base64(self.otp_coa).decode('Latin-1'))
|
||||
print("sn: ", end='')
|
||||
for byte in range(0,12,4):
|
||||
x = self.__getSN(byte)
|
||||
x = x[::-1] # reverse the bytes
|
||||
self.sn = self.sn + x
|
||||
print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
|
||||
print('')
|
||||
try:
|
||||
print("type: " + self.otp_id.decode('Latin-1'))
|
||||
print("idtype: " + binascii.b2a_qp(self.otp_idtype).decode('Latin-1'))
|
||||
print("vid: " + binascii.hexlify(self.otp_vid).decode('Latin-1'))
|
||||
print("pid: "+ binascii.hexlify(self.otp_pid).decode('Latin-1'))
|
||||
print("coa: "+ binascii.b2a_base64(self.otp_coa).decode('Latin-1'))
|
||||
print("sn: ", end='')
|
||||
for byte in range(0,12,4):
|
||||
x = self.__getSN(byte)
|
||||
x = x[::-1] # reverse the bytes
|
||||
self.sn = self.sn + x
|
||||
print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
|
||||
print('')
|
||||
except Exception:
|
||||
# ignore bad character encodings
|
||||
pass
|
||||
print("erase...")
|
||||
self.__erase()
|
||||
|
||||
|
|
|
@ -147,6 +147,7 @@ enum {
|
|||
TONE_BATTERY_WARNING_SLOW_TUNE,
|
||||
TONE_BATTERY_WARNING_FAST_TUNE,
|
||||
TONE_GPS_WARNING_TUNE,
|
||||
TONE_ARMING_FAILURE_TUNE,
|
||||
TONE_NUMBER_OF_TUNES
|
||||
};
|
||||
|
||||
|
|
|
@ -169,6 +169,8 @@ private:
|
|||
|
||||
int _bus; /**< the bus the device is connected to */
|
||||
|
||||
struct mag_report _last_report; /**< used for info() */
|
||||
|
||||
/**
|
||||
* Test whether the device supported by the driver is present at a
|
||||
* specific address.
|
||||
|
@ -870,6 +872,8 @@ HMC5883::collect()
|
|||
}
|
||||
}
|
||||
|
||||
_last_report = new_report;
|
||||
|
||||
/* post a report to the ring */
|
||||
if (_reports->force(&new_report)) {
|
||||
perf_count(_buffer_overflows);
|
||||
|
@ -1042,32 +1046,29 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
|
|||
|
||||
warnx("axes scaling: %.6f %.6f %.6f", (double)scaling[0], (double)scaling[1], (double)scaling[2]);
|
||||
|
||||
/* set back to normal mode */
|
||||
/* Set to 1.1 Gauss */
|
||||
if (OK != ::ioctl(fd, MAGIOCSRANGE, 1)) {
|
||||
warnx("failed to set 1.1 Ga range");
|
||||
goto out;
|
||||
}
|
||||
|
||||
if (OK != ::ioctl(fd, MAGIOCEXSTRAP, 0)) {
|
||||
warnx("failed to disable sensor calibration mode");
|
||||
goto out;
|
||||
}
|
||||
|
||||
/* set scaling in device */
|
||||
mscale_previous.x_scale = scaling[0];
|
||||
mscale_previous.y_scale = scaling[1];
|
||||
mscale_previous.z_scale = scaling[2];
|
||||
|
||||
if (OK != ioctl(filp, MAGIOCSSCALE, (long unsigned int)&mscale_previous)) {
|
||||
warn("WARNING: failed to set new scale / offsets for mag");
|
||||
goto out;
|
||||
}
|
||||
|
||||
ret = OK;
|
||||
|
||||
out:
|
||||
|
||||
if (OK != ioctl(filp, MAGIOCSSCALE, (long unsigned int)&mscale_previous)) {
|
||||
warn("WARNING: failed to set new scale / offsets for mag");
|
||||
}
|
||||
|
||||
/* set back to normal mode */
|
||||
/* Set to 1.1 Gauss */
|
||||
if (OK != ::ioctl(fd, MAGIOCSRANGE, 1)) {
|
||||
warnx("failed to set 1.1 Ga range");
|
||||
}
|
||||
|
||||
if (OK != ::ioctl(fd, MAGIOCEXSTRAP, 0)) {
|
||||
warnx("failed to disable sensor calibration mode");
|
||||
}
|
||||
|
||||
if (ret == OK) {
|
||||
if (!check_scale()) {
|
||||
warnx("mag scale calibration successfully finished.");
|
||||
|
@ -1221,6 +1222,7 @@ HMC5883::print_info()
|
|||
perf_print_counter(_comms_errors);
|
||||
perf_print_counter(_buffer_overflows);
|
||||
printf("poll interval: %u ticks\n", _measure_ticks);
|
||||
printf("output (%.2f %.2f %.2f)\n", (double)_last_report.x, (double)_last_report.y, (double)_last_report.z);
|
||||
printf("offsets (%.2f %.2f %.2f)\n", (double)_scale.x_offset, (double)_scale.y_offset, (double)_scale.z_offset);
|
||||
printf("scaling (%.2f %.2f %.2f) 1/range_scale %.2f range_ga %.2f\n",
|
||||
(double)_scale.x_scale, (double)_scale.y_scale, (double)_scale.z_scale,
|
||||
|
|
|
@ -334,6 +334,7 @@ ToneAlarm::ToneAlarm() :
|
|||
_default_tunes[TONE_BATTERY_WARNING_SLOW_TUNE] = "MBNT100a8"; //battery warning slow
|
||||
_default_tunes[TONE_BATTERY_WARNING_FAST_TUNE] = "MBNT255a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8"; //battery warning fast
|
||||
_default_tunes[TONE_GPS_WARNING_TUNE] = "MFT255L4AAAL1F#"; //gps warning slow
|
||||
_default_tunes[TONE_ARMING_FAILURE_TUNE] = "MFT255L4<<<BAP";
|
||||
|
||||
_tune_names[TONE_STARTUP_TUNE] = "startup"; // startup tune
|
||||
_tune_names[TONE_ERROR_TUNE] = "error"; // ERROR tone
|
||||
|
@ -344,6 +345,7 @@ ToneAlarm::ToneAlarm() :
|
|||
_tune_names[TONE_BATTERY_WARNING_SLOW_TUNE] = "slow_bat"; // battery warning slow
|
||||
_tune_names[TONE_BATTERY_WARNING_FAST_TUNE] = "fast_bat"; // battery warning fast
|
||||
_tune_names[TONE_GPS_WARNING_TUNE] = "gps_warning"; // gps warning
|
||||
_tune_names[TONE_ARMING_FAILURE_TUNE] = "arming_failure"; //fail to arm
|
||||
}
|
||||
|
||||
ToneAlarm::~ToneAlarm()
|
||||
|
|
|
@ -106,7 +106,22 @@ void swap_var(float &d1, float &d2)
|
|||
d2 = tmp;
|
||||
}
|
||||
|
||||
AttPosEKF::AttPosEKF()
|
||||
AttPosEKF::AttPosEKF() :
|
||||
fusionModeGPS(0),
|
||||
covSkipCount(0),
|
||||
EAS2TAS(1.0f),
|
||||
statesInitialised(false),
|
||||
fuseVelData(false),
|
||||
fusePosData(false),
|
||||
fuseHgtData(false),
|
||||
fuseMagData(false),
|
||||
fuseVtasData(false),
|
||||
onGround(true),
|
||||
staticMode(true),
|
||||
useAirspeed(true),
|
||||
useCompass(true),
|
||||
numericalProtection(true),
|
||||
storeIndex(0)
|
||||
{
|
||||
|
||||
}
|
||||
|
|
|
@ -108,7 +108,7 @@ public:
|
|||
Vector3f dVelIMU;
|
||||
Vector3f dAngIMU;
|
||||
float dtIMU; // time lapsed since the last IMU measurement or covariance update (sec)
|
||||
uint8_t fusionModeGPS = 0; // 0 = GPS outputs 3D velocity, 1 = GPS outputs 2D velocity, 2 = GPS outputs no velocity
|
||||
uint8_t fusionModeGPS; // 0 = GPS outputs 3D velocity, 1 = GPS outputs 2D velocity, 2 = GPS outputs no velocity
|
||||
float innovVelPos[6]; // innovation output
|
||||
float varInnovVelPos[6]; // innovation variance output
|
||||
|
||||
|
@ -127,8 +127,8 @@ public:
|
|||
float lonRef; // WGS-84 longitude of reference point (rad)
|
||||
float hgtRef; // WGS-84 height of reference point (m)
|
||||
Vector3f magBias; // states representing magnetometer bias vector in XYZ body axes
|
||||
uint8_t covSkipCount = 0; // Number of state prediction frames (IMU daya updates to skip before doing the covariance prediction
|
||||
float EAS2TAS = 1.0f; // ratio f true to equivalent airspeed
|
||||
uint8_t covSkipCount; // Number of state prediction frames (IMU daya updates to skip before doing the covariance prediction
|
||||
float EAS2TAS; // ratio f true to equivalent airspeed
|
||||
|
||||
// GPS input data variables
|
||||
float gpsCourse;
|
||||
|
@ -141,25 +141,25 @@ public:
|
|||
// Baro input
|
||||
float baroHgt;
|
||||
|
||||
bool statesInitialised = false;
|
||||
bool statesInitialised;
|
||||
|
||||
bool fuseVelData = false; // this boolean causes the posNE and velNED obs to be fused
|
||||
bool fusePosData = false; // this boolean causes the posNE and velNED obs to be fused
|
||||
bool fuseHgtData = false; // this boolean causes the hgtMea obs to be fused
|
||||
bool fuseMagData = false; // boolean true when magnetometer data is to be fused
|
||||
bool fuseVtasData = false; // boolean true when airspeed data is to be fused
|
||||
bool fuseVelData; // this boolean causes the posNE and velNED obs to be fused
|
||||
bool fusePosData; // this boolean causes the posNE and velNED obs to be fused
|
||||
bool fuseHgtData; // this boolean causes the hgtMea obs to be fused
|
||||
bool fuseMagData; // boolean true when magnetometer data is to be fused
|
||||
bool fuseVtasData; // boolean true when airspeed data is to be fused
|
||||
|
||||
bool onGround = true; ///< boolean true when the flight vehicle is on the ground (not flying)
|
||||
bool staticMode = true; ///< boolean true if no position feedback is fused
|
||||
bool useAirspeed = true; ///< boolean true if airspeed data is being used
|
||||
bool useCompass = true; ///< boolean true if magnetometer data is being used
|
||||
bool onGround; ///< boolean true when the flight vehicle is on the ground (not flying)
|
||||
bool staticMode; ///< boolean true if no position feedback is fused
|
||||
bool useAirspeed; ///< boolean true if airspeed data is being used
|
||||
bool useCompass; ///< boolean true if magnetometer data is being used
|
||||
|
||||
struct ekf_status_report current_ekf_state;
|
||||
struct ekf_status_report last_ekf_error;
|
||||
|
||||
bool numericalProtection = true;
|
||||
bool numericalProtection;
|
||||
|
||||
unsigned storeIndex = 0;
|
||||
unsigned storeIndex;
|
||||
|
||||
|
||||
void UpdateStrapdownEquationsNED();
|
||||
|
|
Loading…
Reference in New Issue