mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
Merge remote-tracking branch 'upstream/next' into filnet/LP-29_osgearth_integration
This commit is contained in:
commit
58c880d706
@ -1,23 +1,14 @@
|
||||
|
||||
|
||||
# *************** OpenPilot commits guidelines ***************
|
||||
# *************** LibrePilot commits guidelines ***************
|
||||
# Each commit needs to have a message like the following sample:
|
||||
# OP-1150 UI for thermal calibration: Connect State machine to UI
|
||||
# LP-188 Determine AccelTau based on usage
|
||||
#
|
||||
# It needs to begin with a reference to one or more Jira tickets followed by a short description.
|
||||
# If needed add a longer description in the following lines, after an empty line.
|
||||
#
|
||||
# Before committing, ensure your code is properly formatted using:
|
||||
# Before committing, ensure your code is properly formatted using:
|
||||
# make uncrustify_all
|
||||
# You can format flight or ground code only using respectively
|
||||
# uncrustify_flight or uncrustify_ground
|
||||
#
|
||||
# To automatically create a review, append the following smart commit messages:
|
||||
# +review OPReview
|
||||
#
|
||||
# To append the commit to an existing review, use the following smart commit message:
|
||||
# +review OPReview-NNN
|
||||
# For example "+review OPReview-609"
|
||||
#
|
||||
# *NOTE* leave an empty line between the commit message and "smart commit command"
|
||||
# Smart commits commands need to starts immediately at first column
|
||||
|
||||
|
@ -37,16 +37,26 @@ AuxMagSettingsTypeOptions option;
|
||||
|
||||
void auxmagsupport_reload_settings()
|
||||
{
|
||||
AuxMagSettingsData cal;
|
||||
float magQuat[4];
|
||||
float R[3][3];
|
||||
|
||||
AuxMagSettingsGet(&cal);
|
||||
mag_bias[0] = cal.mag_bias.X;
|
||||
mag_bias[1] = cal.mag_bias.Y;
|
||||
mag_bias[2] = cal.mag_bias.Z;
|
||||
|
||||
// convert the RPY mag board rotation to into a rotation matrix
|
||||
// rotate the vector into the level hover frame (the attitude frame)
|
||||
const float magRpy[3] = { cal.BoardRotation.Roll, cal.BoardRotation.Pitch, cal.BoardRotation.Yaw };
|
||||
RPY2Quaternion(magRpy, magQuat);
|
||||
Quaternion2R(magQuat, R);
|
||||
|
||||
// the mag transform only scales the raw mag values
|
||||
matrix_mult_3x3f((float(*)[3])AuxMagSettingsmag_transformToArray(cal.mag_transform), R, mag_transform);
|
||||
|
||||
// GPSV9, Ext (unused), and Flexi
|
||||
AuxMagSettingsTypeGet(&option);
|
||||
float a[3][3];
|
||||
float b[3][3];
|
||||
float rotz;
|
||||
AuxMagSettingsmag_transformArrayGet((float *)a);
|
||||
AuxMagSettingsOrientationGet(&rotz);
|
||||
rotz = DEG2RAD(rotz);
|
||||
rot_about_axis_z(rotz, b);
|
||||
matrix_mult_3x3f(a, b, mag_transform);
|
||||
AuxMagSettingsmag_biasArrayGet(mag_bias);
|
||||
}
|
||||
|
||||
void auxmagsupport_publish_samples(float mags[3], uint8_t status)
|
||||
|
@ -57,6 +57,9 @@
|
||||
|
||||
#include <attitudesettings.h>
|
||||
#include <revocalibration.h>
|
||||
#include <auxmagsettings.h>
|
||||
#include <auxmagsensor.h>
|
||||
#include <auxmagsupport.h>
|
||||
#include <accelgyrosettings.h>
|
||||
#include <revosettings.h>
|
||||
|
||||
@ -81,7 +84,7 @@
|
||||
#define REGISTER_WDG()
|
||||
#endif
|
||||
|
||||
static const TickType_t sensor_period_ticks = ((uint32_t)1000.0f / PIOS_SENSOR_RATE) / portTICK_RATE_MS;
|
||||
static const TickType_t sensor_period_ticks = ((uint32_t)(1000.0f / PIOS_SENSOR_RATE / (float)portTICK_RATE_MS));
|
||||
|
||||
// Interval in number of sample to recalculate temp bias
|
||||
#define TEMP_CALIB_INTERVAL 30
|
||||
@ -99,8 +102,8 @@ static const float temp_alpha_gyro_accel = LPF_ALPHA(TEMP_DT_GYRO_ACCEL, TEMP_LP
|
||||
#define TEMP_LPF_FC_BARO 5.0f
|
||||
static const float temp_alpha_baro = TEMP_DT_BARO / (TEMP_DT_BARO + 1.0f / (2.0f * M_PI_F * TEMP_LPF_FC_BARO));
|
||||
|
||||
|
||||
#define ZERO_ROT_ANGLE 0.00001f
|
||||
|
||||
// Private types
|
||||
typedef struct {
|
||||
// used to accumulate all samples in a task iteration
|
||||
@ -138,6 +141,7 @@ static void clearContext(sensor_fetch_context *sensor_context);
|
||||
static void handleAccel(float *samples, float temperature);
|
||||
static void handleGyro(float *samples, float temperature);
|
||||
static void handleMag(float *samples, float temperature);
|
||||
static void handleAuxMag(float *samples);
|
||||
static void handleBaro(float sample, float temperature);
|
||||
|
||||
static void updateAccelTempBias(float temperature);
|
||||
@ -151,7 +155,6 @@ RevoCalibrationData cal;
|
||||
AccelGyroSettingsData agcal;
|
||||
|
||||
// These values are initialized by settings but can be updated by the attitude algorithm
|
||||
|
||||
static float mag_bias[3] = { 0, 0, 0 };
|
||||
static float mag_transform[3][3] = {
|
||||
{ 1, 0, 0 }, { 0, 1, 0 }, { 0, 0, 1 }
|
||||
@ -168,9 +171,11 @@ static float gyro_temp_bias[3] = { 0 };
|
||||
static uint8_t accel_temp_calibration_count = 0;
|
||||
static uint8_t gyro_temp_calibration_count = 0;
|
||||
|
||||
// The user specified "Rotate virtual attitude relative to board"
|
||||
static float R[3][3] = {
|
||||
{ 0 }
|
||||
};
|
||||
|
||||
// Variables used to handle baro temperature bias
|
||||
static RevoSettingsBaroTempCorrectionPolynomialData baroCorrection;
|
||||
static RevoSettingsBaroTempCorrectionExtentData baroCorrectionExtent;
|
||||
@ -179,8 +184,6 @@ static float baro_temp_bias = 0;
|
||||
static float baro_temperature = NAN;
|
||||
static uint8_t baro_temp_calibration_count = 0;
|
||||
|
||||
static int8_t rotate = 0;
|
||||
|
||||
/**
|
||||
* Initialise the module. Called before the start function
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
@ -197,7 +200,9 @@ int32_t SensorsInitialize(void)
|
||||
AttitudeSettingsInitialize();
|
||||
AccelGyroSettingsInitialize();
|
||||
|
||||
rotate = 0;
|
||||
// for auxmagsupport.c helpers
|
||||
AuxMagSettingsInitialize();
|
||||
AuxMagSensorInitialize();
|
||||
|
||||
RevoSettingsConnectCallback(&settingsUpdatedCb);
|
||||
RevoCalibrationConnectCallback(&settingsUpdatedCb);
|
||||
@ -258,6 +263,7 @@ static void SensorsTask(__attribute__((unused)) void *parameters)
|
||||
bool sensors_test = true;
|
||||
uint8_t count = 0;
|
||||
LL_FOREACH((PIOS_SENSORS_Instance *)sensors_list, sensor) {
|
||||
RELOAD_WDG(); // mag tests on I2C have 200+(7x10)ms delay calls in them
|
||||
sensors_test &= PIOS_SENSORS_Test(sensor);
|
||||
count++;
|
||||
}
|
||||
@ -361,20 +367,29 @@ static void processSamples3d(sensor_fetch_context *sensor_context, const PIOS_SE
|
||||
PIOS_SENSORS_GetScales(sensor, scales, MAX_SENSORS_PER_INSTANCE);
|
||||
float inv_count = 1.0f / (float)sensor_context->count;
|
||||
if ((sensor->type & PIOS_SENSORS_TYPE_3AXIS_ACCEL) ||
|
||||
(sensor->type == PIOS_SENSORS_TYPE_3AXIS_MAG)) {
|
||||
(sensor->type == PIOS_SENSORS_TYPE_3AXIS_MAG) ||
|
||||
(sensor->type == PIOS_SENSORS_TYPE_3AXIS_AUXMAG)) {
|
||||
float t = inv_count * scales[0];
|
||||
samples[0] = ((float)sensor_context->accum[0].x * t);
|
||||
samples[1] = ((float)sensor_context->accum[0].y * t);
|
||||
samples[2] = ((float)sensor_context->accum[0].z * t);
|
||||
temperature = (float)sensor_context->temperature * inv_count * 0.01f;
|
||||
if (sensor->type == PIOS_SENSORS_TYPE_3AXIS_MAG) {
|
||||
switch (sensor->type) {
|
||||
case PIOS_SENSORS_TYPE_3AXIS_MAG:
|
||||
handleMag(samples, temperature);
|
||||
PERF_MEASURE_PERIOD(counterMagPeriod);
|
||||
return;
|
||||
} else {
|
||||
|
||||
case PIOS_SENSORS_TYPE_3AXIS_AUXMAG:
|
||||
handleAuxMag(samples);
|
||||
PERF_MEASURE_PERIOD(counterMagPeriod);
|
||||
return;
|
||||
|
||||
default:
|
||||
PERF_TRACK_VALUE(counterAccelSamples, sensor_context->count);
|
||||
PERF_MEASURE_PERIOD(counterAccelPeriod);
|
||||
handleAccel(samples, temperature);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
@ -458,6 +473,11 @@ static void handleMag(float *samples, float temperature)
|
||||
MagSensorSet(&mag);
|
||||
}
|
||||
|
||||
static void handleAuxMag(float *samples)
|
||||
{
|
||||
auxmagsupport_publish_samples(samples, AUXMAGSENSOR_STATUS_OK);
|
||||
}
|
||||
|
||||
static void handleBaro(float sample, float temperature)
|
||||
{
|
||||
updateBaroTempBias(temperature);
|
||||
@ -535,58 +555,47 @@ static void updateBaroTempBias(float temperature)
|
||||
}
|
||||
baro_temp_calibration_count--;
|
||||
}
|
||||
|
||||
/**
|
||||
* Locally cache some variables from the AtttitudeSettings object
|
||||
* Locally cache some variables from the AttitudeSettings object
|
||||
*/
|
||||
static void settingsUpdatedCb(__attribute__((unused)) UAVObjEvent *objEv)
|
||||
{
|
||||
RevoCalibrationGet(&cal);
|
||||
AccelGyroSettingsGet(&agcal);
|
||||
mag_bias[0] = cal.mag_bias.X;
|
||||
mag_bias[1] = cal.mag_bias.Y;
|
||||
mag_bias[2] = cal.mag_bias.Z;
|
||||
|
||||
AccelGyroSettingsGet(&agcal);
|
||||
accel_temp_calibrated = (agcal.temp_calibrated_extent.max - agcal.temp_calibrated_extent.min > .1f) &&
|
||||
(fabsf(agcal.accel_temp_coeff.X) > 1e-9f || fabsf(agcal.accel_temp_coeff.Y) > 1e-9f || fabsf(agcal.accel_temp_coeff.Z) > 1e-9f);
|
||||
|
||||
gyro_temp_calibrated = (agcal.temp_calibrated_extent.max - agcal.temp_calibrated_extent.min > .1f) &&
|
||||
(fabsf(agcal.gyro_temp_coeff.X) > 1e-9f || fabsf(agcal.gyro_temp_coeff.Y) > 1e-9f ||
|
||||
fabsf(agcal.gyro_temp_coeff.Z) > 1e-9f || fabsf(agcal.gyro_temp_coeff.Z2) > 1e-9f);
|
||||
|
||||
|
||||
// convert BoardRotation ("rotate virtual") into a quaternion
|
||||
AttitudeSettingsData attitudeSettings;
|
||||
AttitudeSettingsGet(&attitudeSettings);
|
||||
|
||||
// Indicates not to expend cycles on rotation
|
||||
if (fabsf(attitudeSettings.BoardRotation.Roll) < ZERO_ROT_ANGLE
|
||||
&& fabsf(attitudeSettings.BoardRotation.Pitch) < ZERO_ROT_ANGLE &&
|
||||
fabsf(attitudeSettings.BoardRotation.Yaw) < ZERO_ROT_ANGLE) {
|
||||
rotate = 0;
|
||||
} else {
|
||||
rotate = 1;
|
||||
}
|
||||
|
||||
const float rpy[3] = { attitudeSettings.BoardRotation.Roll,
|
||||
attitudeSettings.BoardRotation.Pitch,
|
||||
attitudeSettings.BoardRotation.Yaw };
|
||||
|
||||
float rotationQuat[4];
|
||||
RPY2Quaternion(rpy, rotationQuat);
|
||||
|
||||
if (fabsf(attitudeSettings.BoardLevelTrim.Roll) > ZERO_ROT_ANGLE ||
|
||||
fabsf(attitudeSettings.BoardLevelTrim.Pitch) > ZERO_ROT_ANGLE) {
|
||||
float trimQuat[4];
|
||||
float sumQuat[4];
|
||||
rotate = 1;
|
||||
// convert BoardLevelTrim ("board level calibration") into a quaternion
|
||||
float trimQuat[4];
|
||||
float sumQuat[4];
|
||||
const float trimRpy[3] = { attitudeSettings.BoardLevelTrim.Roll, attitudeSettings.BoardLevelTrim.Pitch, 0.0f };
|
||||
// do we actually want to include BoardLevelTrim in the mag rotation? BoardRotation yes, but BoardLevelTrim?
|
||||
// and is BoardLevelTrim done at the correct point in the sequence of rotations?
|
||||
RPY2Quaternion(trimRpy, trimQuat);
|
||||
|
||||
const float trimRpy[3] = { attitudeSettings.BoardLevelTrim.Roll, attitudeSettings.BoardLevelTrim.Pitch, 0.0f };
|
||||
RPY2Quaternion(trimRpy, trimQuat);
|
||||
// add the boardrotation and boardtrim rotations and put them into a rotation matrix
|
||||
quat_mult(rotationQuat, trimQuat, sumQuat);
|
||||
Quaternion2R(sumQuat, R);
|
||||
|
||||
quat_mult(rotationQuat, trimQuat, sumQuat);
|
||||
Quaternion2R(sumQuat, R);
|
||||
} else {
|
||||
Quaternion2R(rotationQuat, R);
|
||||
}
|
||||
// mag_transform is only a scaling
|
||||
// so add the scaling, and store the result in mag_transform for run time use
|
||||
matrix_mult_3x3f((float(*)[3])RevoCalibrationmag_transformToArray(cal.mag_transform), R, mag_transform);
|
||||
|
||||
RevoSettingsBaroTempCorrectionPolynomialGet(&baroCorrection);
|
||||
|
@ -183,6 +183,10 @@ static void systemTask(__attribute__((unused)) void *parameters)
|
||||
vTaskDelay(10);
|
||||
}
|
||||
|
||||
#ifndef PIOS_INCLUDE_WDG
|
||||
// if no watchdog is enabled, don't reset watchdog in MODULE_TASKCREATE_ALL loop
|
||||
#define PIOS_WDG_Clear()
|
||||
#endif
|
||||
/* create all modules thread */
|
||||
MODULE_TASKCREATE_ALL;
|
||||
|
||||
|
@ -45,6 +45,8 @@ typedef struct {
|
||||
uint32_t port_id;
|
||||
uint8_t slave_num;
|
||||
uint8_t CTRLB;
|
||||
uint16_t magCountMax;
|
||||
uint16_t magCount;
|
||||
volatile bool data_ready;
|
||||
} pios_hmc5x83_dev_data_t;
|
||||
|
||||
@ -66,6 +68,7 @@ const PIOS_SENSORS_Driver PIOS_HMC5x83_Driver = {
|
||||
.get_scale = PIOS_HMC5x83_driver_get_scale,
|
||||
.is_polled = true,
|
||||
};
|
||||
|
||||
/**
|
||||
* Allocate the device setting structure
|
||||
* @return pios_hmc5x83_dev_data_t pointer to newly created structure
|
||||
@ -104,20 +107,73 @@ pios_hmc5x83_dev_t PIOS_HMC5x83_Init(const struct pios_hmc5x83_cfg *cfg, uint32_
|
||||
dev->cfg = cfg; // store config before enabling interrupt
|
||||
dev->port_id = port_id;
|
||||
dev->slave_num = slave_num;
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
PIOS_EXTI_Init(cfg->exti_cfg);
|
||||
#endif
|
||||
|
||||
int32_t val = PIOS_HMC5x83_Config(dev);
|
||||
PIOS_Assert(val == 0);
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
if (cfg->exti_cfg) {
|
||||
PIOS_EXTI_Init(cfg->exti_cfg);
|
||||
} else
|
||||
#endif /* PIOS_HMC5X83_HAS_GPIOS */
|
||||
{
|
||||
// if PIOS_SENSOR_RATE is defined, there is a sensor loop that is called at that frequency
|
||||
// and "is data available" can simply return false a few times to save some CPU
|
||||
#ifdef PIOS_SENSOR_RATE
|
||||
// for external mags that have no interrupt line, just poll them with a timer
|
||||
// use the configured Output Data Rate to calculate the number of interations (of the main sensor task loop)
|
||||
// to return false, before returning true
|
||||
uint16_t rate100;
|
||||
switch (cfg->M_ODR) {
|
||||
case PIOS_HMC5x83_ODR_0_75:
|
||||
rate100 = 75;
|
||||
break;
|
||||
case PIOS_HMC5x83_ODR_1_5:
|
||||
rate100 = 150;
|
||||
break;
|
||||
case PIOS_HMC5x83_ODR_3:
|
||||
rate100 = 300;
|
||||
break;
|
||||
case PIOS_HMC5x83_ODR_7_5:
|
||||
rate100 = 750;
|
||||
break;
|
||||
case PIOS_HMC5x83_ODR_15:
|
||||
rate100 = 1500;
|
||||
break;
|
||||
case PIOS_HMC5x83_ODR_30:
|
||||
rate100 = 3000;
|
||||
break;
|
||||
default:
|
||||
case PIOS_HMC5x83_ODR_75:
|
||||
rate100 = 7500;
|
||||
break;
|
||||
}
|
||||
// if the application sensor rate is fast enough to warrant skipping some slow hardware sensor reads
|
||||
if ((PIOS_SENSOR_RATE * 100.0f / 3.0f) > rate100) {
|
||||
// count the number of "return false" up to this number
|
||||
dev->magCountMax = ((uint16_t)PIOS_SENSOR_RATE * 100 / rate100) + 1;
|
||||
} else {
|
||||
// return true every time (do a hardware sensor poll every time)
|
||||
dev->magCountMax = 1;
|
||||
}
|
||||
#else /* PIOS_SENSOR_RATE */
|
||||
// return true every time (do a hardware sensor poll every time)
|
||||
dev->magCountMax = 1;
|
||||
#endif /* PIOS_SENSOR_RATE */
|
||||
// with this counter
|
||||
dev->magCount = 0;
|
||||
}
|
||||
|
||||
if (PIOS_HMC5x83_Config(dev) != 0) {
|
||||
return (pios_hmc5x83_dev_t)NULL;
|
||||
}
|
||||
|
||||
dev->data_ready = false;
|
||||
return (pios_hmc5x83_dev_t)dev;
|
||||
}
|
||||
|
||||
void PIOS_HMC5x83_Register(pios_hmc5x83_dev_t handler)
|
||||
void PIOS_HMC5x83_Register(pios_hmc5x83_dev_t handler, PIOS_SENSORS_TYPE sensortype)
|
||||
{
|
||||
PIOS_SENSORS_Register(&PIOS_HMC5x83_Driver, PIOS_SENSORS_TYPE_3AXIS_MAG, handler);
|
||||
if (handler) {
|
||||
PIOS_SENSORS_Register(&PIOS_HMC5x83_Driver, sensortype, handler);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -212,6 +268,52 @@ static int32_t PIOS_HMC5x83_Config(pios_hmc5x83_dev_data_t *dev)
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void PIOS_HMC5x83_Orient(enum PIOS_HMC5X83_ORIENTATION orientation, int16_t in[3], int16_t out[3])
|
||||
{
|
||||
switch (orientation) {
|
||||
case PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP:
|
||||
out[0] = in[2];
|
||||
out[1] = in[0];
|
||||
out[2] = -in[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_SOUTH_EAST_UP:
|
||||
out[0] = -in[0];
|
||||
out[1] = in[2];
|
||||
out[2] = -in[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_WEST_SOUTH_UP:
|
||||
out[0] = -in[2];
|
||||
out[1] = -in[0];
|
||||
out[2] = -in[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_NORTH_WEST_UP:
|
||||
out[0] = in[0];
|
||||
out[1] = -in[2];
|
||||
out[2] = -in[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_EAST_SOUTH_DOWN:
|
||||
out[0] = in[2];
|
||||
out[1] = -in[0];
|
||||
out[2] = in[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_SOUTH_WEST_DOWN:
|
||||
out[0] = -in[0];
|
||||
out[1] = -in[2];
|
||||
out[2] = in[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_WEST_NORTH_DOWN:
|
||||
out[0] = -in[2];
|
||||
out[1] = in[0];
|
||||
out[2] = in[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_NORTH_EAST_DOWN:
|
||||
out[0] = in[0];
|
||||
out[1] = in[2];
|
||||
out[2] = in[1];
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Read current X, Z, Y values (in that order)
|
||||
* \param[in] dev device handler
|
||||
@ -265,50 +367,14 @@ int32_t PIOS_HMC5x83_ReadMag(pios_hmc5x83_dev_t handler, int16_t out[3])
|
||||
temp[i] = v;
|
||||
}
|
||||
|
||||
switch (dev->cfg->Orientation) {
|
||||
case PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP:
|
||||
out[0] = temp[2];
|
||||
out[1] = temp[0];
|
||||
out[2] = -temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_SOUTH_EAST_UP:
|
||||
out[0] = -temp[0];
|
||||
out[1] = temp[2];
|
||||
out[2] = -temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_WEST_SOUTH_UP:
|
||||
out[0] = -temp[2];
|
||||
out[1] = -temp[0];
|
||||
out[2] = -temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_NORTH_WEST_UP:
|
||||
out[0] = temp[0];
|
||||
out[1] = -temp[2];
|
||||
out[2] = -temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_EAST_SOUTH_DOWN:
|
||||
out[0] = temp[2];
|
||||
out[1] = -temp[0];
|
||||
out[2] = temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_SOUTH_WEST_DOWN:
|
||||
out[0] = -temp[0];
|
||||
out[1] = -temp[2];
|
||||
out[2] = temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_WEST_NORTH_DOWN:
|
||||
out[0] = -temp[2];
|
||||
out[1] = temp[0];
|
||||
out[2] = temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_NORTH_EAST_DOWN:
|
||||
out[0] = temp[0];
|
||||
out[1] = temp[2];
|
||||
out[2] = temp[1];
|
||||
break;
|
||||
}
|
||||
PIOS_HMC5x83_Orient(dev->cfg->Orientation, temp, out);
|
||||
|
||||
// This should not be necessary but for some reason it is coming out of continuous conversion mode
|
||||
// "This should not be necessary but for some reason it is coming out of continuous conversion mode"
|
||||
//
|
||||
// By default the chip is in single read mode meaning after reading from it once, it will go idle to save power.
|
||||
// Once idle, we have write to it to turn it on before we can read from it again.
|
||||
// To conserve current between measurements, the device is placed in a state similar to idle mode, but the
|
||||
// Mode Register is not changed to Idle Mode. That is, MD[n] bits are unchanged.
|
||||
dev->cfg->Driver->Write(handler, PIOS_HMC5x83_MODE_REG, PIOS_HMC5x83_MODE_CONTINUOUS);
|
||||
|
||||
return 0;
|
||||
@ -334,11 +400,23 @@ uint8_t PIOS_HMC5x83_ReadID(pios_hmc5x83_dev_t handler, uint8_t out[4])
|
||||
* \return true if new data is available
|
||||
* \return false if new data is not available
|
||||
*/
|
||||
bool PIOS_HMC5x83_NewDataAvailable(pios_hmc5x83_dev_t handler)
|
||||
bool PIOS_HMC5x83_NewDataAvailable(__attribute__((unused)) pios_hmc5x83_dev_t handler)
|
||||
{
|
||||
pios_hmc5x83_dev_data_t *dev = dev_validate(handler);
|
||||
|
||||
return dev->data_ready;
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
if (dev->cfg->exti_cfg) { // if this device has an interrupt line attached, then wait for interrupt to say data is ready
|
||||
return dev->data_ready;
|
||||
} else
|
||||
#endif /* PIOS_HMC5X83_HAS_GPIOS */
|
||||
{ // else poll to see if data is ready or just say "true" and set polling interval elsewhere
|
||||
if (++(dev->magCount) >= dev->magCountMax) {
|
||||
dev->magCount = 0;
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -435,6 +513,7 @@ int32_t PIOS_HMC5x83_Test(pios_hmc5x83_dev_t handler)
|
||||
return failed;
|
||||
}
|
||||
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
/**
|
||||
* @brief IRQ Handler
|
||||
*/
|
||||
@ -443,8 +522,10 @@ bool PIOS_HMC5x83_IRQHandler(pios_hmc5x83_dev_t handler)
|
||||
pios_hmc5x83_dev_data_t *dev = dev_validate(handler);
|
||||
|
||||
dev->data_ready = true;
|
||||
|
||||
return false;
|
||||
}
|
||||
#endif /* PIOS_HMC5X83_HAS_GPIOS */
|
||||
|
||||
#ifdef PIOS_INCLUDE_SPI
|
||||
int32_t PIOS_HMC5x83_SPI_Read(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t *buffer, uint8_t len);
|
||||
@ -529,8 +610,8 @@ int32_t PIOS_HMC5x83_SPI_Write(pios_hmc5x83_dev_t handler, uint8_t address, uint
|
||||
return 0;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
int32_t PIOS_HMC5x83_I2C_Read(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t *buffer, uint8_t len);
|
||||
int32_t PIOS_HMC5x83_I2C_Write(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t buffer);
|
||||
|
||||
|
@ -95,6 +95,9 @@
|
||||
#define PIOS_HMC5x83_Sensitivity_5_6Ga 330 // LSB/Ga
|
||||
#define PIOS_HMC5x83_Sensitivity_8_1Ga 230 // LSB/Ga --> NOT RECOMMENDED
|
||||
|
||||
/* Status Register */
|
||||
#define PIOS_HMC5x83_DATAOUT_STATUS_RDY 0x01
|
||||
|
||||
typedef uintptr_t pios_hmc5x83_dev_t;
|
||||
|
||||
struct pios_hmc5x83_io_driver {
|
||||
@ -137,7 +140,7 @@ struct pios_hmc5x83_cfg {
|
||||
|
||||
/* Public Functions */
|
||||
extern pios_hmc5x83_dev_t PIOS_HMC5x83_Init(const struct pios_hmc5x83_cfg *cfg, uint32_t port_id, uint8_t device_num);
|
||||
extern void PIOS_HMC5x83_Register(pios_hmc5x83_dev_t handler);
|
||||
extern void PIOS_HMC5x83_Register(pios_hmc5x83_dev_t handler, PIOS_SENSORS_TYPE sensortype);
|
||||
|
||||
extern bool PIOS_HMC5x83_NewDataAvailable(pios_hmc5x83_dev_t handler);
|
||||
extern int32_t PIOS_HMC5x83_ReadMag(pios_hmc5x83_dev_t handler, int16_t out[3]);
|
||||
|
@ -100,10 +100,12 @@ extern void StartModules();
|
||||
initTaskDone = 1; \
|
||||
}
|
||||
|
||||
#define MODULE_TASKCREATE_ALL \
|
||||
#define MODULE_TASKCREATE_ALL \
|
||||
{ for (initmodule_t *fn = __module_initcall_start; fn < __module_initcall_end; fn++) { \
|
||||
if (fn->fn_tinit) { \
|
||||
(fn->fn_tinit)(); } \
|
||||
if (fn->fn_tinit) { \
|
||||
(fn->fn_tinit)(); \
|
||||
PIOS_WDG_Clear(); \
|
||||
} \
|
||||
} \
|
||||
}
|
||||
|
||||
|
@ -54,15 +54,16 @@ typedef struct PIOS_SENSORS_Driver {
|
||||
} PIOS_SENSORS_Driver;
|
||||
|
||||
typedef enum PIOS_SENSORS_TYPE {
|
||||
PIOS_SENSORS_TYPE_3AXIS_ACCEL = 0x01,
|
||||
PIOS_SENSORS_TYPE_3AXIS_GYRO = 0x02,
|
||||
PIOS_SENSORS_TYPE_3AXIS_ACCEL = 0x01,
|
||||
PIOS_SENSORS_TYPE_3AXIS_GYRO = 0x02,
|
||||
PIOS_SENSORS_TYPE_3AXIS_GYRO_ACCEL = 0x03,
|
||||
PIOS_SENSORS_TYPE_3AXIS_MAG = 0x04,
|
||||
PIOS_SENSORS_TYPE_1AXIS_BARO = 0x08,
|
||||
PIOS_SENSORS_TYPE_3AXIS_MAG = 0x04,
|
||||
PIOS_SENSORS_TYPE_3AXIS_AUXMAG = 0x08,
|
||||
PIOS_SENSORS_TYPE_1AXIS_BARO = 0x10,
|
||||
} PIOS_SENSORS_TYPE;
|
||||
|
||||
#define PIOS_SENSORS_TYPE_1D (PIOS_SENSORS_TYPE_1AXIS_BARO)
|
||||
#define PIOS_SENSORS_TYPE_3D (PIOS_SENSORS_TYPE_3AXIS_ACCEL | PIOS_SENSORS_TYPE_3AXIS_GYRO | PIOS_SENSORS_TYPE_3AXIS_MAG)
|
||||
#define PIOS_SENSORS_TYPE_3D (PIOS_SENSORS_TYPE_3AXIS_ACCEL | PIOS_SENSORS_TYPE_3AXIS_GYRO | PIOS_SENSORS_TYPE_3AXIS_MAG | PIOS_SENSORS_TYPE_3AXIS_AUXMAG)
|
||||
|
||||
typedef struct PIOS_SENSORS_Instance {
|
||||
const PIOS_SENSORS_Driver *driver;
|
||||
|
@ -711,6 +711,12 @@ static bool i2c_adapter_wait_for_stopped(struct pios_i2c_adapter *i2c_adapter)
|
||||
|
||||
static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
// retry with wait code from
|
||||
// TauLabs 20150718 - Prevent F3 I2C Init Lockup #1728
|
||||
uint8_t retry_count;
|
||||
uint8_t retry_count_clk;
|
||||
static const uint8_t MAX_I2C_RETRY_COUNT = 10;
|
||||
|
||||
/* Reset the I2C block */
|
||||
I2C_DeInit(i2c_adapter->cfg->regs);
|
||||
|
||||
@ -731,11 +737,13 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter)
|
||||
/* have to be repeated (due to futher bus errors) but better than clocking 0xFF into an */
|
||||
/* ESC */
|
||||
// bool sda_hung = GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) == Bit_RESET;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) == Bit_RESET) {
|
||||
retry_count_clk = 0;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) == Bit_RESET && (retry_count_clk++ < MAX_I2C_RETRY_COUNT)) {
|
||||
retry_count = 0;
|
||||
/* Set clock high and wait for any clock stretching to finish. */
|
||||
GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin);
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET) {
|
||||
;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET && (retry_count++ < MAX_I2C_RETRY_COUNT)) {
|
||||
PIOS_DELAY_WaituS(1);
|
||||
}
|
||||
PIOS_DELAY_WaituS(2);
|
||||
|
||||
@ -759,12 +767,14 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter)
|
||||
/* Set data and clock high and wait for any clock stretching to finish. */
|
||||
GPIO_SetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin);
|
||||
GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin);
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET) {
|
||||
;
|
||||
retry_count = 0;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET && (retry_count++ < MAX_I2C_RETRY_COUNT)) {
|
||||
PIOS_DELAY_WaituS(1);
|
||||
}
|
||||
/* Wait for data to be high */
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) != Bit_SET) {
|
||||
;
|
||||
retry_count = 0;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) != Bit_SET && (retry_count++ < MAX_I2C_RETRY_COUNT)) {
|
||||
PIOS_DELAY_WaituS(1);
|
||||
}
|
||||
|
||||
|
||||
|
@ -390,6 +390,7 @@ static const struct i2c_adapter_transition i2c_adapter_transitions[I2C_STATE_NUM
|
||||
},
|
||||
};
|
||||
|
||||
|
||||
static void go_fsm_fault(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
#if defined(I2C_HALT_ON_ERRORS)
|
||||
@ -401,6 +402,7 @@ static void go_fsm_fault(struct pios_i2c_adapter *i2c_adapter)
|
||||
i2c_adapter_reset_bus(i2c_adapter);
|
||||
}
|
||||
|
||||
|
||||
static void go_bus_error(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
/* Note that this transfer has hit a bus error */
|
||||
@ -409,6 +411,7 @@ static void go_bus_error(struct pios_i2c_adapter *i2c_adapter)
|
||||
i2c_adapter_reset_bus(i2c_adapter);
|
||||
}
|
||||
|
||||
|
||||
static void go_stopping(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
#ifdef USE_FREERTOS
|
||||
@ -431,12 +434,14 @@ static void go_stopping(struct pios_i2c_adapter *i2c_adapter)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static void go_stopped(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, DISABLE);
|
||||
I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, ENABLE);
|
||||
}
|
||||
|
||||
|
||||
static void go_starting(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn);
|
||||
@ -465,6 +470,7 @@ static void go_starting(struct pios_i2c_adapter *i2c_adapter)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* Common to 'more' and 'last' transaction */
|
||||
static void go_r_any_txn_addr(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
@ -477,24 +483,28 @@ static void go_r_any_txn_addr(struct pios_i2c_adapter *i2c_adapter)
|
||||
I2C_Send7bitAddress(i2c_adapter->cfg->regs, (i2c_adapter->active_txn->addr) << 1, I2C_Direction_Receiver);
|
||||
}
|
||||
|
||||
|
||||
static void go_r_more_txn_pre_one(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, DISABLE);
|
||||
I2C_GenerateSTART(i2c_adapter->cfg->regs, ENABLE);
|
||||
}
|
||||
|
||||
|
||||
static void go_r_last_txn_pre_one(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, DISABLE);
|
||||
I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE);
|
||||
}
|
||||
|
||||
|
||||
/* Common to 'more' and 'last' transaction */
|
||||
static void go_r_any_txn_pre_first(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, ENABLE);
|
||||
}
|
||||
|
||||
|
||||
/* Common to 'more' and 'last' transaction */
|
||||
static void go_r_any_txn_pre_middle(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
@ -508,6 +518,7 @@ static void go_r_any_txn_pre_middle(struct pios_i2c_adapter *i2c_adapter)
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte);
|
||||
}
|
||||
|
||||
|
||||
static void go_r_more_txn_pre_last(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_byte);
|
||||
@ -526,6 +537,7 @@ static void go_r_more_txn_pre_last(struct pios_i2c_adapter *i2c_adapter)
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte);
|
||||
}
|
||||
|
||||
|
||||
static void go_r_last_txn_pre_last(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_byte);
|
||||
@ -544,6 +556,7 @@ static void go_r_last_txn_pre_last(struct pios_i2c_adapter *i2c_adapter)
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte);
|
||||
}
|
||||
|
||||
|
||||
/* Common to 'more' and 'last' transaction */
|
||||
static void go_r_any_txn_post_last(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
@ -562,6 +575,7 @@ static void go_r_any_txn_post_last(struct pios_i2c_adapter *i2c_adapter)
|
||||
i2c_adapter->active_txn++;
|
||||
}
|
||||
|
||||
|
||||
/* Common to 'more' and 'last' transaction */
|
||||
static void go_w_any_txn_addr(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
@ -574,6 +588,7 @@ static void go_w_any_txn_addr(struct pios_i2c_adapter *i2c_adapter)
|
||||
I2C_Send7bitAddress(i2c_adapter->cfg->regs, (i2c_adapter->active_txn->addr) << 1, I2C_Direction_Transmitter);
|
||||
}
|
||||
|
||||
|
||||
static void go_w_any_txn_middle(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_byte);
|
||||
@ -589,6 +604,7 @@ static void go_w_any_txn_middle(struct pios_i2c_adapter *i2c_adapter)
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte);
|
||||
}
|
||||
|
||||
|
||||
static void go_w_more_txn_last(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_byte);
|
||||
@ -607,6 +623,7 @@ static void go_w_more_txn_last(struct pios_i2c_adapter *i2c_adapter)
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn);
|
||||
}
|
||||
|
||||
|
||||
static void go_w_last_txn_last(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_byte);
|
||||
@ -625,6 +642,7 @@ static void go_w_last_txn_last(struct pios_i2c_adapter *i2c_adapter)
|
||||
i2c_adapter->active_byte++;
|
||||
}
|
||||
|
||||
|
||||
static void go_nack(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
i2c_adapter->nack = true;
|
||||
@ -633,6 +651,7 @@ static void go_nack(struct pios_i2c_adapter *i2c_adapter)
|
||||
I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE);
|
||||
}
|
||||
|
||||
|
||||
static void i2c_adapter_inject_event(struct pios_i2c_adapter *i2c_adapter, enum i2c_adapter_event event)
|
||||
{
|
||||
PIOS_IRQ_Disable();
|
||||
@ -668,6 +687,7 @@ static void i2c_adapter_inject_event(struct pios_i2c_adapter *i2c_adapter, enum
|
||||
PIOS_IRQ_Enable();
|
||||
}
|
||||
|
||||
|
||||
static void i2c_adapter_process_auto(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
PIOS_IRQ_Disable();
|
||||
@ -684,12 +704,14 @@ static void i2c_adapter_process_auto(struct pios_i2c_adapter *i2c_adapter)
|
||||
PIOS_IRQ_Enable();
|
||||
}
|
||||
|
||||
|
||||
static void i2c_adapter_fsm_init(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
i2c_adapter_reset_bus(i2c_adapter);
|
||||
i2c_adapter->curr_state = I2C_STATE_STOPPED;
|
||||
}
|
||||
|
||||
|
||||
static bool i2c_adapter_wait_for_stopped(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
uint32_t guard;
|
||||
@ -712,8 +734,15 @@ static bool i2c_adapter_wait_for_stopped(struct pios_i2c_adapter *i2c_adapter)
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
// retry with wait code from
|
||||
// TauLabs 20150718 - Prevent F3 I2C Init Lockup #1728
|
||||
uint8_t retry_count;
|
||||
uint8_t retry_count_clk;
|
||||
static const uint8_t MAX_I2C_RETRY_COUNT = 10;
|
||||
|
||||
/* Reset the I2C block */
|
||||
I2C_DeInit(i2c_adapter->cfg->regs);
|
||||
|
||||
@ -734,11 +763,13 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter)
|
||||
/* have to be repeated (due to futher bus errors) but better than clocking 0xFF into an */
|
||||
/* ESC */
|
||||
// bool sda_hung = GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) == Bit_RESET;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) == Bit_RESET) {
|
||||
retry_count_clk = 0;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) == Bit_RESET && (retry_count_clk++ < MAX_I2C_RETRY_COUNT)) {
|
||||
retry_count = 0;
|
||||
/* Set clock high and wait for any clock stretching to finish. */
|
||||
GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin);
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET) {
|
||||
;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET && (retry_count++ < MAX_I2C_RETRY_COUNT)) {
|
||||
PIOS_DELAY_WaituS(1);
|
||||
}
|
||||
PIOS_DELAY_WaituS(2);
|
||||
|
||||
@ -762,12 +793,14 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter)
|
||||
/* Set data and clock high and wait for any clock stretching to finish. */
|
||||
GPIO_SetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin);
|
||||
GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin);
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET) {
|
||||
;
|
||||
retry_count = 0;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET && (retry_count++ < MAX_I2C_RETRY_COUNT)) {
|
||||
PIOS_DELAY_WaituS(1);
|
||||
}
|
||||
/* Wait for data to be high */
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) != Bit_SET) {
|
||||
;
|
||||
retry_count = 0;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) != Bit_SET && (retry_count++ < MAX_I2C_RETRY_COUNT)) {
|
||||
PIOS_DELAY_WaituS(1);
|
||||
}
|
||||
|
||||
|
||||
@ -818,6 +851,7 @@ static bool i2c_adapter_fsm_terminated(struct pios_i2c_adapter *i2c_adapter)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
uint32_t i2c_cb_count = 0;
|
||||
static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
@ -872,6 +906,7 @@ static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter)
|
||||
return (!i2c_adapter->bus_error) && semaphore_success;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Logs the last N state transitions and N IRQ events due to
|
||||
* an error condition
|
||||
@ -936,6 +971,7 @@ static bool PIOS_I2C_validate(struct pios_i2c_adapter *i2c_adapter)
|
||||
return i2c_adapter->magic == PIOS_I2C_DEV_MAGIC;
|
||||
}
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS) && 0
|
||||
static struct pios_i2c_dev *PIOS_I2C_alloc(void)
|
||||
{
|
||||
|
@ -84,7 +84,7 @@
|
||||
// #define PIOS_INCLUDE_MPU6000
|
||||
// #define PIOS_MPU6000_ACCEL
|
||||
/* #define PIOS_INCLUDE_HMC5843 */
|
||||
// #define PIOS_INCLUDE_HMC5X83
|
||||
#define PIOS_INCLUDE_HMC5X83
|
||||
// #define PIOS_HMC5X83_HAS_GPIOS
|
||||
/* #define PIOS_INCLUDE_BMP085 */
|
||||
// #define PIOS_INCLUDE_MS5611
|
||||
|
@ -36,6 +36,7 @@
|
||||
#include <pios_oplinkrcvr_priv.h>
|
||||
#include <taskinfo.h>
|
||||
#include <pios_callbackscheduler.h>
|
||||
#include <auxmagsettings.h>
|
||||
|
||||
#ifdef PIOS_INCLUDE_INSTRUMENTATION
|
||||
#include <pios_instrumentation.h>
|
||||
@ -92,8 +93,16 @@ void PIOS_ADC_DMC_irq_handler(void)
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
#include "pios_hmc5x83.h"
|
||||
pios_hmc5x83_dev_t onboard_mag = 0;
|
||||
pios_hmc5x83_dev_t external_mag = 0;
|
||||
|
||||
bool pios_board_internal_mag_handler()
|
||||
{
|
||||
return PIOS_HMC5x83_IRQHandler(onboard_mag);
|
||||
}
|
||||
|
||||
static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
.vector = PIOS_HMC5x83_IRQHandler,
|
||||
.vector = pios_board_internal_mag_handler,
|
||||
.line = EXTI_Line7,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
@ -123,14 +132,30 @@ static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_cfg = {
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_internal_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
};
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_external_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = NULL,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75, // if you change this for auxmag, change AUX_MAG_SKIP in sensors.c
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP, // ENU for GPSV9, WND for typical I2C mag
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
@ -654,11 +679,40 @@ void PIOS_Board_Init(void)
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_I2C:
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
{
|
||||
if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
PIOS_DELAY_WaitmS(50); // this was after the other PIOS_I2C_Init(), so I copied it here too
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
// leave this here even if PIOS_INCLUDE_HMC5X83 is undefined
|
||||
// to avoid making something else fail when HMC5X83 is removed
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
// get auxmag type
|
||||
AuxMagSettingsTypeOptions option;
|
||||
AuxMagSettingsInitialize();
|
||||
AuxMagSettingsTypeGet(&option);
|
||||
// if the aux mag type is FlexiPort then set it up
|
||||
if (option == AUXMAGSETTINGS_TYPE_FLEXI) {
|
||||
// attach the 5x83 mag to the previously inited I2C2
|
||||
external_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_external_cfg, pios_i2c_flexiport_adapter_id, 0);
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
// add this sensor to the sensor task's list
|
||||
// be careful that you don't register a slow, unimportant sensor after registering the fastest sensor
|
||||
// and before registering some other fast and important sensor
|
||||
// as that would cause delay and time jitter for the second fast sensor
|
||||
PIOS_HMC5x83_Register(external_mag, PIOS_SENSORS_TYPE_3AXIS_AUXMAG);
|
||||
// mag alarm is cleared later, so use I2C
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_I2C, (external_mag) ? SYSTEMALARMS_ALARM_OK : SYSTEMALARMS_ALARM_WARNING);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_GPS:
|
||||
@ -882,6 +936,7 @@ void PIOS_Board_Init(void)
|
||||
};
|
||||
GPIO_Init(GPIOA, &gpioA8);
|
||||
|
||||
// init I2C1 for use with the internal mag and baro
|
||||
if (PIOS_I2C_Init(&pios_i2c_mag_pressure_adapter_id, &pios_i2c_mag_pressure_adapter_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
@ -892,8 +947,24 @@ void PIOS_Board_Init(void)
|
||||
PIOS_ADC_Init(&pios_adc_cfg);
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
// leave this here even if PIOS_INCLUDE_HMC5X83 is undefined
|
||||
// to avoid making something else fail when HMC5X83 is removed
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
PIOS_HMC5x83_Init(&pios_hmc5x83_cfg, pios_i2c_mag_pressure_adapter_id, 0);
|
||||
// attach the 5x83 mag to the previously inited I2C1
|
||||
onboard_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_internal_cfg, pios_i2c_mag_pressure_adapter_id, 0);
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
// add this sensor to the sensor task's list
|
||||
PIOS_HMC5x83_Register(onboard_mag, PIOS_SENSORS_TYPE_3AXIS_MAG);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_MS5611)
|
||||
|
@ -81,7 +81,7 @@
|
||||
/* #define PIOS_INCLUDE_MPU6000 */
|
||||
/* #define PIOS_MPU6000_ACCEL */
|
||||
/* #define PIOS_INCLUDE_HMC5843 */
|
||||
#define PIOS_INCLUDE_HMC5X83
|
||||
/* #define PIOS_INCLUDE_HMC5X83 */
|
||||
/* #define PIOS_HMC5X83_HAS_GPIOS */
|
||||
#define PIOS_INCLUDE_BMP085
|
||||
/* #define PIOS_INCLUDE_MS5611 */
|
||||
|
@ -36,7 +36,7 @@
|
||||
#include <pios_oplinkrcvr_priv.h>
|
||||
#include <taskinfo.h>
|
||||
#include <pios_ws2811.h>
|
||||
|
||||
#include <auxmagsettings.h>
|
||||
|
||||
#ifdef PIOS_INCLUDE_INSTRUMENTATION
|
||||
#include <pios_instrumentation.h>
|
||||
@ -55,12 +55,11 @@
|
||||
/**
|
||||
* Sensor configurations
|
||||
*/
|
||||
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
|
||||
#include "pios_adc_priv.h"
|
||||
void PIOS_ADC_DMC_irq_handler(void);
|
||||
void DMA2_Stream4_IRQHandler(void) __attribute__((alias("PIOS_ADC_DMC_irq_handler")));
|
||||
|
||||
struct pios_adc_cfg pios_adc_cfg = {
|
||||
.adc_dev = ADC1,
|
||||
.dma = {
|
||||
@ -84,22 +83,25 @@ struct pios_adc_cfg pios_adc_cfg = {
|
||||
.half_flag = DMA_IT_HTIF4,
|
||||
.full_flag = DMA_IT_TCIF4,
|
||||
};
|
||||
|
||||
void PIOS_ADC_DMC_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_ADC_DMA_Handler();
|
||||
}
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_ADC) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
#include "pios_hmc5x83.h"
|
||||
pios_hmc5x83_dev_t onboard_mag = 0;
|
||||
pios_hmc5x83_dev_t onboard_mag = 0;
|
||||
pios_hmc5x83_dev_t external_mag = 0;
|
||||
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
bool pios_board_internal_mag_handler()
|
||||
{
|
||||
return PIOS_HMC5x83_IRQHandler(onboard_mag);
|
||||
}
|
||||
|
||||
static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
.vector = pios_board_internal_mag_handler,
|
||||
.line = EXTI_Line7,
|
||||
@ -130,15 +132,32 @@ static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* PIOS_HMC5X83_HAS_GPIOS */
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_cfg = {
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_internal_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
};
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_external_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = NULL,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75, // if you change this for auxmag, change AUX_MAG_SKIP in sensors.c
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP, // ENU for GPSV9, WND for typical I2C mag
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
@ -247,7 +266,6 @@ uint32_t pios_com_rf_id = 0;
|
||||
uint32_t pios_com_bridge_id = 0;
|
||||
uint32_t pios_com_overo_id = 0;
|
||||
uint32_t pios_com_hkosd_id = 0;
|
||||
|
||||
uint32_t pios_com_vcp_id = 0;
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
@ -368,7 +386,6 @@ void PIOS_Board_Init(void)
|
||||
PIOS_LED_Init(led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
|
||||
#ifdef PIOS_INCLUDE_INSTRUMENTATION
|
||||
PIOS_Instrumentation_Init(PIOS_INSTRUMENTATION_MAX_COUNTERS);
|
||||
#endif
|
||||
@ -400,6 +417,7 @@ void PIOS_Board_Init(void)
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
PIOS_RTC_Init(&pios_rtc_main_cfg);
|
||||
#endif
|
||||
|
||||
/* IAP System Setup */
|
||||
PIOS_IAP_Init();
|
||||
// check for safe mode commands from gcs
|
||||
@ -411,6 +429,7 @@ void PIOS_Board_Init(void)
|
||||
PIOS_IAP_WriteBootCmd(1, 0);
|
||||
PIOS_IAP_WriteBootCmd(2, 0);
|
||||
}
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_Init();
|
||||
#endif
|
||||
@ -471,11 +490,40 @@ void PIOS_Board_Init(void)
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_I2C:
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
{
|
||||
if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
PIOS_DELAY_WaitmS(50); // this was after the other PIOS_I2C_Init(), so I copied it here too
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
// leave this here even if PIOS_INCLUDE_HMC5X83 is undefined
|
||||
// to avoid making something else fail when HMC5X83 is removed
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
// get auxmag type
|
||||
AuxMagSettingsTypeOptions option;
|
||||
AuxMagSettingsInitialize();
|
||||
AuxMagSettingsTypeGet(&option);
|
||||
// if the aux mag type is FlexiPort then set it up
|
||||
if (option == AUXMAGSETTINGS_TYPE_FLEXI) {
|
||||
// attach the 5x83 mag to the previously inited I2C2
|
||||
external_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_external_cfg, pios_i2c_flexiport_adapter_id, 0);
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
// add this sensor to the sensor task's list
|
||||
// be careful that you don't register a slow, unimportant sensor after registering the fastest sensor
|
||||
// and before registering some other fast and important sensor
|
||||
// as that would cause delay and time jitter for the second fast sensor
|
||||
PIOS_HMC5x83_Register(external_mag, PIOS_SENSORS_TYPE_3AXIS_AUXMAG);
|
||||
// mag alarm is cleared later, so use I2C
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_I2C, (external_mag) ? SYSTEMALARMS_ALARM_OK : SYSTEMALARMS_ALARM_WARNING);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_GPS:
|
||||
@ -662,7 +710,6 @@ void PIOS_Board_Init(void)
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
|
||||
/* Configure main USART port */
|
||||
uint8_t hwsettings_mainport;
|
||||
HwSettingsRM_MainPortGet(&hwsettings_mainport);
|
||||
@ -724,7 +771,6 @@ void PIOS_Board_Init(void)
|
||||
GPIO_WriteBit(pios_sbus_cfg.inv.gpio, pios_sbus_cfg.inv.init.GPIO_Pin, pios_sbus_cfg.gpio_inv_disable);
|
||||
}
|
||||
|
||||
|
||||
/* Initalize the RFM22B radio COM device. */
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
|
||||
@ -838,7 +884,6 @@ void PIOS_Board_Init(void)
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PWM)
|
||||
|
||||
const struct pios_servo_cfg *pios_servo_cfg;
|
||||
// default to servo outputs only
|
||||
pios_servo_cfg = &pios_servo_cfg_out;
|
||||
@ -933,10 +978,10 @@ void PIOS_Board_Init(void)
|
||||
};
|
||||
GPIO_Init(GPIOA, &gpioA8);
|
||||
|
||||
// init I2C1 for use with the internal mag and baro
|
||||
if (PIOS_I2C_Init(&pios_i2c_mag_pressure_adapter_id, &pios_i2c_mag_pressure_adapter_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
PIOS_DELAY_WaitmS(50);
|
||||
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
@ -949,9 +994,24 @@ void PIOS_Board_Init(void)
|
||||
PIOS_MPU6000_Register();
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
// leave this here even if PIOS_INCLUDE_HMC5X83 is undefined
|
||||
// to avoid making something else fail when HMC5X83 is removed
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
onboard_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_cfg, pios_i2c_mag_pressure_adapter_id, 0);
|
||||
PIOS_HMC5x83_Register(onboard_mag);
|
||||
// attach the 5x83 mag to the previously inited I2C1
|
||||
onboard_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_internal_cfg, pios_i2c_mag_pressure_adapter_id, 0);
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
// add this sensor to the sensor task's list
|
||||
PIOS_HMC5x83_Register(onboard_mag, PIOS_SENSORS_TYPE_3AXIS_MAG);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_MS5611)
|
||||
|
@ -84,7 +84,7 @@
|
||||
// #define PIOS_INCLUDE_MPU6000
|
||||
// #define PIOS_MPU6000_ACCEL
|
||||
/* #define PIOS_INCLUDE_HMC5843 */
|
||||
// #define PIOS_INCLUDE_HMC5X83
|
||||
#define PIOS_INCLUDE_HMC5X83
|
||||
// #define PIOS_HMC5X83_HAS_GPIOS
|
||||
/* #define PIOS_INCLUDE_BMP085 */
|
||||
#define PIOS_INCLUDE_MS5611
|
||||
|
@ -38,6 +38,7 @@
|
||||
#include <pios_ws2811.h>
|
||||
#include <sanitycheck.h>
|
||||
#include <actuatorsettings.h>
|
||||
#include <auxmagsettings.h>
|
||||
|
||||
#ifdef PIOS_INCLUDE_INSTRUMENTATION
|
||||
#include <pios_instrumentation.h>
|
||||
@ -92,9 +93,26 @@ void PIOS_ADC_DMC_irq_handler(void)
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_ADC_DMA_Handler();
|
||||
}
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_ADC) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
#include "pios_hmc5x83.h"
|
||||
pios_hmc5x83_dev_t external_mag = 0;
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_external_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = NULL,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75, // if you change this for auxmag, change AUX_MAG_SKIP in sensors.c
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP, // ENU for GPSV9, WND for typical I2C mag
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
/**
|
||||
* Configuration for the MS5611 chip
|
||||
*/
|
||||
@ -360,6 +378,7 @@ void PIOS_Board_Init(void)
|
||||
PIOS_IAP_WriteBootCmd(1, 0);
|
||||
PIOS_IAP_WriteBootCmd(2, 0);
|
||||
}
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_Init();
|
||||
#endif
|
||||
@ -617,11 +636,40 @@ void PIOS_Board_Init(void)
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_I2C:
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
{
|
||||
if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
PIOS_DELAY_WaitmS(50); // this was after the other PIOS_I2C_Init(), so I copied it here too
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
// leave this here even if PIOS_INCLUDE_HMC5X83 is undefined
|
||||
// to avoid making something else fail when HMC5X83 is removed
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
// get auxmag type
|
||||
AuxMagSettingsTypeOptions option;
|
||||
AuxMagSettingsInitialize();
|
||||
AuxMagSettingsTypeGet(&option);
|
||||
// if the aux mag type is FlexiPort then set it up
|
||||
if (option == AUXMAGSETTINGS_TYPE_FLEXI) {
|
||||
// attach the 5x83 mag to the previously inited I2C2
|
||||
external_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_external_cfg, pios_i2c_flexiport_adapter_id, 0);
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
// add this sensor to the sensor task's list
|
||||
// be careful that you don't register a slow, unimportant sensor after registering the fastest sensor
|
||||
// and before registering some other fast and important sensor
|
||||
// as that would cause delay and time jitter for the second fast sensor
|
||||
PIOS_HMC5x83_Register(external_mag, PIOS_SENSORS_TYPE_3AXIS_AUXMAG);
|
||||
// mag alarm is cleared later, so use I2C
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_I2C, (external_mag) ? SYSTEMALARMS_ALARM_OK : SYSTEMALARMS_ALARM_WARNING);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_GPS:
|
||||
|
@ -31,6 +31,7 @@
|
||||
#include <hwsettings.h>
|
||||
#include <manualcontrolsettings.h>
|
||||
#include <taskinfo.h>
|
||||
#include <auxmagsettings.h>
|
||||
|
||||
/*
|
||||
* Pull in the board-specific static HW definitions.
|
||||
@ -84,8 +85,10 @@ void PIOS_ADC_DMC_irq_handler(void)
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
#include "pios_hmc5x83.h"
|
||||
|
||||
pios_hmc5x83_dev_t onboard_mag = 0;
|
||||
pios_hmc5x83_dev_t onboard_mag = 0;
|
||||
pios_hmc5x83_dev_t external_mag = 0;
|
||||
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
bool pios_board_internal_mag_handler()
|
||||
{
|
||||
return PIOS_HMC5x83_IRQHandler(onboard_mag);
|
||||
@ -120,15 +123,32 @@ static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* PIOS_HMC5X83_HAS_GPIOS */
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_cfg = {
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_internal_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
};
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_external_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = NULL,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75, // if you change this for auxmag, change AUX_MAG_SKIP in sensors.c
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
@ -753,14 +773,39 @@ void PIOS_Board_Init(void)
|
||||
break;
|
||||
case HWSETTINGS_RV_FLEXIPORT_I2C:
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
{
|
||||
if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
PIOS_DELAY_WaitmS(50); // this was after the other PIOS_I2C_Init(), so I copied it here too
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
// leave this here even if PIOS_INCLUDE_HMC5X83 is undefined
|
||||
// to avoid making something else fail when HMC5X83 is removed
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
// get auxmag type
|
||||
AuxMagSettingsTypeOptions option;
|
||||
AuxMagSettingsInitialize();
|
||||
AuxMagSettingsTypeGet(&option);
|
||||
// if the aux mag type is FlexiPort then set it up
|
||||
if (option == AUXMAGSETTINGS_TYPE_FLEXI) {
|
||||
// attach the 5x83 mag to the previously inited I2C2
|
||||
external_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_external_cfg, pios_i2c_flexiport_adapter_id, 0);
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
// add this sensor to the sensor task's list
|
||||
PIOS_HMC5x83_Register(external_mag, PIOS_SENSORS_TYPE_3AXIS_AUXMAG);
|
||||
// mag alarm is cleared later, so use I2C
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_I2C, (external_mag) ? SYSTEMALARMS_ALARM_OK : SYSTEMALARMS_ALARM_WARNING);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RV_FLEXIPORT_DSM:
|
||||
// TODO: Define the various Channelgroup for Revo dsm inputs and handle here
|
||||
PIOS_Board_configure_dsm(&pios_usart_dsm_flexi_cfg, &pios_dsm_flexi_cfg,
|
||||
@ -879,10 +924,12 @@ void PIOS_Board_Init(void)
|
||||
PIOS_DEBUG_Init(pios_tim_servoport_all_pins, NELEMENTS(pios_tim_servoport_all_pins));
|
||||
#endif
|
||||
|
||||
// init I2C1 for use with the internal mag
|
||||
if (PIOS_I2C_Init(&pios_i2c_mag_adapter_id, &pios_i2c_mag_adapter_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
// init I2C1 for use with the internal baro
|
||||
if (PIOS_I2C_Init(&pios_i2c_pressure_adapter_id, &pios_i2c_pressure_adapter_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
@ -893,9 +940,24 @@ void PIOS_Board_Init(void)
|
||||
PIOS_ADC_Init(&pios_adc_cfg);
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
// leave this here even if PIOS_INCLUDE_HMC5X83 is undefined
|
||||
// to avoid making something else fail when HMC5X83 is removed
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
onboard_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_cfg, pios_i2c_mag_adapter_id, 0);
|
||||
PIOS_HMC5x83_Register(onboard_mag);
|
||||
// attach the 5x83 mag to the previously inited I2C1
|
||||
onboard_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_internal_cfg, pios_i2c_mag_adapter_id, 0);
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
// add this sensor to the sensor task's list
|
||||
PIOS_HMC5x83_Register(onboard_mag, PIOS_SENSORS_TYPE_3AXIS_MAG);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_MS5611)
|
||||
|
199
ground/gcs/src/libs/utils/textbubbleslider.cpp
Normal file
199
ground/gcs/src/libs/utils/textbubbleslider.cpp
Normal file
@ -0,0 +1,199 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file textbubbleslider.h
|
||||
* @author Tau Labs, http://taulabs.org Copyright (C) 2013.
|
||||
* @brief Creates a slider with a text bubble showing the slider value
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup
|
||||
* @{
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include <QDebug>
|
||||
#include <QPainter>
|
||||
#include <QtGui>
|
||||
#include <qmath.h>
|
||||
|
||||
#include "textbubbleslider.h"
|
||||
|
||||
/**
|
||||
* @brief TextBubbleSlider::TextBubbleSlider Constructs a regular text-bubble slider
|
||||
* @param parent
|
||||
*/
|
||||
TextBubbleSlider::TextBubbleSlider(QWidget *parent) :
|
||||
QSlider(parent)
|
||||
{
|
||||
QFontDatabase::addApplicationFont(":/utils/fonts/PTS75F.ttf");
|
||||
|
||||
construct();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief TextBubbleSlider::TextBubbleSlider Constructs a text-bubble slider that copys
|
||||
* all relevant data from the previous slider
|
||||
* @param copySlider
|
||||
* @param parent
|
||||
*/
|
||||
TextBubbleSlider::TextBubbleSlider(QSlider *copySlider, QWidget *parent) :
|
||||
QSlider(parent)
|
||||
{
|
||||
construct();
|
||||
|
||||
// Copy settings
|
||||
setSizePolicy(copySlider->sizePolicy());
|
||||
setMinimumSize(copySlider->minimumSize());
|
||||
setMaximumSize(copySlider->maximumSize());
|
||||
setFocusPolicy(copySlider->focusPolicy());
|
||||
setOrientation(copySlider->orientation());
|
||||
setMaximum(copySlider->maximum());
|
||||
setMinimum(copySlider->minimum());
|
||||
setToolTip(copySlider->toolTip());
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief TextBubbleSlider::construct This function needs to be called from all constructors. It
|
||||
* provides a single point where settings can be changed.
|
||||
*/
|
||||
void TextBubbleSlider::construct()
|
||||
{
|
||||
font = QFont("PT Sans", 13, QFont::Bold);
|
||||
slideHandleMargin = 2; // This is a dubious way to set the margin. In reality, it should be read from the style sheet.
|
||||
}
|
||||
|
||||
TextBubbleSlider::~TextBubbleSlider()
|
||||
{}
|
||||
|
||||
|
||||
/**
|
||||
* @brief numIntegerDigits Counts the number of digits in an integer
|
||||
* @param number Input integer
|
||||
* @return Number of digits in input integer
|
||||
*/
|
||||
unsigned int numIntegerDigits(int number)
|
||||
{
|
||||
unsigned int digits = 0;
|
||||
|
||||
// If there is a negative sign, be sure to include it in digit count
|
||||
if (number < 0) {
|
||||
digits = 1;
|
||||
}
|
||||
|
||||
while (number) {
|
||||
number /= 10;
|
||||
digits++;
|
||||
}
|
||||
|
||||
return digits;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief TextBubbleSlider::setMaxPixelWidth Sets maximum pixel width for slider handle
|
||||
*/
|
||||
void TextBubbleSlider::setMaxPixelWidth()
|
||||
{
|
||||
// Calculate maximum number of digits possible in string
|
||||
int maxNumDigits = numIntegerDigits(maximum()) > numIntegerDigits(minimum()) ? numIntegerDigits(maximum()) : numIntegerDigits(minimum());
|
||||
|
||||
// Generate string with maximum pixel width. Suppose that "0" is
|
||||
// the widest number in pixels.
|
||||
QString maximumWidthString;
|
||||
|
||||
for (int i = 0; i < maxNumDigits; i++) {
|
||||
maximumWidthString.append("0");
|
||||
}
|
||||
|
||||
// Calculate maximum possible pixel width for string.
|
||||
QFontMetrics fontMetrics(font);
|
||||
maximumFontWidth = fontMetrics.width(QString("%1").arg(maximumWidthString));
|
||||
maximumFontHeight = fontMetrics.height();
|
||||
|
||||
// Override stylesheet slider handle width
|
||||
slideHandleWidth = maximumFontWidth + 6;
|
||||
setStyleSheet(QString("QSlider::handle:horizontal { width: %1px; margin: -5px 0;}").arg(slideHandleWidth));
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief TextBubbleSlider::setMinimum Reimplements setMinimum. Ensures that the slider
|
||||
* handle is the correct size for the text field.
|
||||
* @param max maximum
|
||||
*/
|
||||
void TextBubbleSlider::setMinimum(int max)
|
||||
{
|
||||
// Pass value on to QSlider
|
||||
QSlider::setMinimum(max);
|
||||
|
||||
// Reset handler size
|
||||
setMaxPixelWidth();
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief TextBubbleSlider::setMaximum Reimplements setMaximum. Ensures that the slider
|
||||
* handle is the correct size for the text field.
|
||||
* @param max maximum
|
||||
*/
|
||||
void TextBubbleSlider::setMaximum(int max)
|
||||
{
|
||||
// Pass value on to QSlider
|
||||
QSlider::setMaximum(max);
|
||||
|
||||
// Reset handler size
|
||||
setMaxPixelWidth();
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief TextBubbleSlider::paintEvent Reimplements QSlider::paintEvent.
|
||||
* @param bob
|
||||
*/
|
||||
void TextBubbleSlider::paintEvent(QPaintEvent *paintEvent)
|
||||
{
|
||||
// Pass paint event on to QSlider
|
||||
QSlider::paintEvent(paintEvent);
|
||||
|
||||
/* Add numbers on top of handler */
|
||||
|
||||
// Calculate pixel position for text.
|
||||
int sliderWidth = width();
|
||||
int sliderHeight = height();
|
||||
double valuePos;
|
||||
|
||||
if (!invertedAppearance()) {
|
||||
valuePos = (slideHandleWidth - maximumFontWidth) / 2 + slideHandleMargin + // First part centers text in handle...
|
||||
(value() - minimum()) / (double)(maximum() - minimum()) * (sliderWidth - (slideHandleWidth + slideHandleMargin) - 1); // ... and second part moves text with handle
|
||||
} else {
|
||||
valuePos = (slideHandleWidth - maximumFontWidth) / 2 + slideHandleMargin + // First part centers text in handle...
|
||||
(maximum() - value()) / (double)(maximum() - minimum()) * (sliderWidth - (slideHandleWidth + slideHandleMargin) - 1); // ... and second part moves text with handle
|
||||
}
|
||||
|
||||
// Create painter and set font
|
||||
QPainter painter(this);
|
||||
painter.setFont(font);
|
||||
painter.setPen(QPen(QColor(80, 80, 80)));
|
||||
|
||||
// Draw neutral value text. Vertically center it in the handle
|
||||
QString neutralStringWidth = QString("%1").arg(value());
|
||||
QFontMetrics fontMetrics(font);
|
||||
int textWidth = fontMetrics.width(neutralStringWidth);
|
||||
painter.drawText(QRectF(valuePos + maximumFontWidth - textWidth, ceil((sliderHeight - maximumFontHeight) / 2.0), textWidth, maximumFontHeight),
|
||||
neutralStringWidth);
|
||||
}
|
61
ground/gcs/src/libs/utils/textbubbleslider.h
Normal file
61
ground/gcs/src/libs/utils/textbubbleslider.h
Normal file
@ -0,0 +1,61 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file textbubbleslider.h
|
||||
* @author Tau Labs, http://taulabs.org Copyright (C) 2013.
|
||||
* @brief Creates a slider with a text bubble showing the slider value
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup
|
||||
* @{
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef TEXTBUBBLESLIDER_H
|
||||
#define TEXTBUBBLESLIDER_H
|
||||
|
||||
#include "utils_global.h"
|
||||
|
||||
#include <QSlider>
|
||||
#include <QtDesigner/QDesignerExportWidget>
|
||||
|
||||
class QTCREATOR_UTILS_EXPORT TextBubbleSlider : public QSlider {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit TextBubbleSlider(QWidget *parent = 0);
|
||||
explicit TextBubbleSlider(QSlider *, QWidget *parent = 0);
|
||||
void construct();
|
||||
~TextBubbleSlider();
|
||||
|
||||
void setMinimum(int);
|
||||
void setMaximum(int);
|
||||
|
||||
protected:
|
||||
void paintEvent(QPaintEvent *event);
|
||||
|
||||
private:
|
||||
void setMaxPixelWidth();
|
||||
|
||||
QFont font;
|
||||
int maximumFontWidth;
|
||||
int maximumFontHeight;
|
||||
int slideHandleWidth;
|
||||
int slideHandleMargin;
|
||||
};
|
||||
|
||||
#endif // TEXTBUBBLESLIDER_H
|
@ -57,7 +57,8 @@ SOURCES += \
|
||||
hostosinfo.cpp \
|
||||
logfile.cpp \
|
||||
crc.cpp \
|
||||
mustache.cpp
|
||||
mustache.cpp \
|
||||
textbubbleslider.cpp
|
||||
|
||||
SOURCES += xmlconfig.cpp
|
||||
|
||||
@ -120,7 +121,8 @@ HEADERS += \
|
||||
hostosinfo.h \
|
||||
logfile.h \
|
||||
crc.h \
|
||||
mustache.h
|
||||
mustache.h \
|
||||
textbubbleslider.h
|
||||
|
||||
HEADERS += xmlconfig.h
|
||||
|
||||
|
@ -1,5 +1,6 @@
|
||||
<RCC>
|
||||
<qresource prefix="/utils" >
|
||||
<file>images/removesubmitfield.png</file>
|
||||
<file>fonts/PTS75F.ttf</file>
|
||||
</qresource>
|
||||
</RCC>
|
||||
|
@ -49,7 +49,7 @@
|
||||
#define STICK_MAX_MOVE 8
|
||||
|
||||
#define CHANNEL_NUMBER_NONE 0
|
||||
#define DEFAULT_FLIGHT_MODE_NUMBER 3
|
||||
#define DEFAULT_FLIGHT_MODE_NUMBER 0
|
||||
|
||||
ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
ConfigTaskWidget(parent),
|
||||
@ -276,6 +276,16 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
m_txFlightMode->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setZValue(-10);
|
||||
|
||||
m_txFlightModeCountBG = new QGraphicsSvgItem();
|
||||
m_txFlightModeCountBG->setParentItem(m_txBackground);
|
||||
m_txFlightModeCountBG->setSharedRenderer(m_renderer);
|
||||
m_txFlightModeCountBG->setElementId("fm_count_bg");
|
||||
l_scene->addItem(m_txFlightModeCountBG);
|
||||
|
||||
m_txFlightModeCountText = new QGraphicsSimpleTextItem("?", m_txFlightModeCountBG);
|
||||
m_txFlightModeCountText->setBrush(QColor(40, 40, 40));
|
||||
m_txFlightModeCountText->setFont(QFont("Arial Bold"));
|
||||
|
||||
m_txArrows = new QGraphicsSvgItem();
|
||||
m_txArrows->setParentItem(m_txBackground);
|
||||
m_txArrows->setSharedRenderer(m_renderer);
|
||||
@ -315,6 +325,20 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
orig = Matrix.mapRect(orig);
|
||||
m_txFlightModeROrig.translate(orig.x(), orig.y());
|
||||
|
||||
orig = m_renderer->boundsOnElement("fm_count_bg");
|
||||
Matrix = m_renderer->matrixForElement("fm_count_bg");
|
||||
orig = Matrix.mapRect(orig);
|
||||
m_txFlightModeCountBGOrig.translate(orig.x(), orig.y());
|
||||
m_txFlightModeCountBG->setTransform(m_txFlightModeCountBGOrig, false);
|
||||
|
||||
QRectF flightModeBGRect = m_txFlightModeCountBG->boundingRect();
|
||||
QRectF flightModeTextRect = m_txFlightModeCountText->boundingRect();
|
||||
qreal scale = 2.5;
|
||||
m_txFlightModeCountTextOrig.translate(flightModeBGRect.width() - (flightModeBGRect.height() / 2), flightModeBGRect.height() / 2);
|
||||
m_txFlightModeCountTextOrig.scale(scale, scale);
|
||||
m_txFlightModeCountTextOrig.translate(-flightModeTextRect.width() / 2, -flightModeTextRect.height() / 2);
|
||||
m_txFlightModeCountText->setTransform(m_txFlightModeCountTextOrig, false);
|
||||
|
||||
orig = m_renderer->boundsOnElement("rjoy");
|
||||
Matrix = m_renderer->matrixForElement("rjoy");
|
||||
orig = Matrix.mapRect(orig);
|
||||
@ -388,6 +412,9 @@ void ConfigInputWidget::resetTxControls()
|
||||
m_txFlightMode->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig, false);
|
||||
m_txArrows->setVisible(false);
|
||||
m_txFlightModeCountText->setText("?");
|
||||
m_txFlightModeCountText->setVisible(false);
|
||||
m_txFlightModeCountBG->setVisible(false);
|
||||
}
|
||||
|
||||
ConfigInputWidget::~ConfigInputWidget()
|
||||
@ -562,6 +589,7 @@ void ConfigInputWidget::wzNext()
|
||||
}
|
||||
break;
|
||||
case wizardIdentifyCenter:
|
||||
resetFlightModeSettings();
|
||||
wizardSetUpStep(wizardIdentifyLimits);
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
@ -608,7 +636,7 @@ void ConfigInputWidget::wzBack()
|
||||
wizardTearDownStep(wizardStep);
|
||||
}
|
||||
|
||||
// State transitions for next button
|
||||
// State transitions for back button
|
||||
switch (wizardStep) {
|
||||
case wizardChooseType:
|
||||
wizardSetUpStep(wizardWelcome);
|
||||
@ -630,6 +658,7 @@ void ConfigInputWidget::wzBack()
|
||||
wizardSetUpStep(wizardIdentifyCenter);
|
||||
break;
|
||||
case wizardIdentifyInverted:
|
||||
resetFlightModeSettings();
|
||||
wizardSetUpStep(wizardIdentifyLimits);
|
||||
break;
|
||||
case wizardFinish:
|
||||
@ -1099,6 +1128,38 @@ void ConfigInputWidget::identifyLimits()
|
||||
manualSettingsData.ChannelMin[i] = manualCommandData.Channel[i];
|
||||
}
|
||||
}
|
||||
// Flightmode channel
|
||||
if (i == ManualControlSettings::CHANNELGROUPS_FLIGHTMODE) {
|
||||
bool newFlightModeValue = true;
|
||||
// Avoid duplicate values too close and error due to RcTx drift
|
||||
int minSpacing = 100; // 100µs
|
||||
for (int pos = 0; pos < manualSettingsData.FlightModeNumber + 1; ++pos) {
|
||||
if (flightModeSignalValue[pos] == 0) {
|
||||
// A new flightmode value can be set now
|
||||
for (int checkpos = 0; checkpos < manualSettingsData.FlightModeNumber + 1; ++checkpos) {
|
||||
// Check if value is already used, MinSpacing needed between values.
|
||||
if ((flightModeSignalValue[checkpos] < manualCommandData.Channel[i] + minSpacing) &&
|
||||
(flightModeSignalValue[checkpos] > manualCommandData.Channel[i] - minSpacing)) {
|
||||
newFlightModeValue = false;
|
||||
}
|
||||
}
|
||||
// Be sure FlightModeNumber is < FlightModeSettings::FLIGHTMODEPOSITION_NUMELEM (6)
|
||||
if ((manualSettingsData.FlightModeNumber < FlightModeSettings::FLIGHTMODEPOSITION_NUMELEM) && newFlightModeValue) {
|
||||
// Start from 0, erase previous count
|
||||
if (pos == 0) {
|
||||
manualSettingsData.FlightModeNumber = 0;
|
||||
}
|
||||
// Store new value and increase FlightModeNumber
|
||||
flightModeSignalValue[pos] = manualCommandData.Channel[i];
|
||||
manualSettingsData.FlightModeNumber++;
|
||||
// Show flight mode number
|
||||
m_txFlightModeCountText->setText(QString().number(manualSettingsData.FlightModeNumber));
|
||||
m_txFlightModeCountText->setVisible(true);
|
||||
m_txFlightModeCountBG->setVisible(true);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
}
|
||||
@ -1488,13 +1549,16 @@ void ConfigInputWidget::moveSticks()
|
||||
Q_ASSERT(0);
|
||||
break;
|
||||
}
|
||||
if (flightStatusData.FlightMode == flightModeSettingsData.FlightModePosition[0]) {
|
||||
if ((flightStatusData.FlightMode == flightModeSettingsData.FlightModePosition[0]) ||
|
||||
(flightStatusData.FlightMode == flightModeSettingsData.FlightModePosition[5])) {
|
||||
m_txFlightMode->setElementId("flightModeLeft");
|
||||
m_txFlightMode->setTransform(m_txFlightModeLOrig, false);
|
||||
} else if (flightStatusData.FlightMode == flightModeSettingsData.FlightModePosition[1]) {
|
||||
} else if ((flightStatusData.FlightMode == flightModeSettingsData.FlightModePosition[1]) ||
|
||||
(flightStatusData.FlightMode == flightModeSettingsData.FlightModePosition[4])) {
|
||||
m_txFlightMode->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig, false);
|
||||
} else if (flightStatusData.FlightMode == flightModeSettingsData.FlightModePosition[2]) {
|
||||
} else if ((flightStatusData.FlightMode == flightModeSettingsData.FlightModePosition[2]) ||
|
||||
(flightStatusData.FlightMode == flightModeSettingsData.FlightModePosition[3])) {
|
||||
m_txFlightMode->setElementId("flightModeRight");
|
||||
m_txFlightMode->setTransform(m_txFlightModeROrig, false);
|
||||
}
|
||||
@ -1666,12 +1730,15 @@ void ConfigInputWidget::updatePositionSlider()
|
||||
if (sp->objectName() == "channelNeutral") {
|
||||
if (count == 4) {
|
||||
sp->setStyleSheet(
|
||||
"QSlider::groove:horizontal {border: 2px solid rgb(196, 196, 196); height: 12px; border-radius: 4px; "
|
||||
"QSlider::groove:horizontal {border: 2px solid rgb(196, 196, 196); margin: 0px 23px 0px 23px; height: 12px; border-radius: 5px; "
|
||||
"border-image:url(:/configgadget/images/flightmode_bg" + fmNumber + ".png); }"
|
||||
"QSlider::add-page:horizontal { background: none; border: none; }"
|
||||
"QSlider::sub-page:horizontal { background: none; border: none; }"
|
||||
"QSlider::handle:horizontal { background: rgba(196, 196, 196, 255); width: 10px; height: 28px; "
|
||||
"margin: -3px -2px; border-radius: 3px; border: 1px solid #777; }");
|
||||
"QSlider::handle:horizontal { background: qlineargradient(x1:0, y1:0, x2:1, y2:0, "
|
||||
"stop: 0 rgba(196, 196, 196, 180), stop: 0.45 rgba(196, 196, 196, 180), "
|
||||
"stop: 0.46 rgba(255,0,0,100), stop: 0.54 rgba(255,0,0,100), "
|
||||
"stop: 0.55 rgba(196, 196, 196, 180), stop: 1 rgba(196, 196, 196, 180)); "
|
||||
"width: 46px; height: 28px; margin: -6px -23px -6px -23px; border-radius: 5px; border: 1px solid #777; }");
|
||||
count++;
|
||||
} else {
|
||||
count++;
|
||||
@ -1838,9 +1905,19 @@ void ConfigInputWidget::resetChannelSettings()
|
||||
for (unsigned int channel = 0; channel < ManualControlSettings::CHANNELNUMBER_NUMELEM; channel++) {
|
||||
manualSettingsData.ChannelGroups[channel] = ManualControlSettings::CHANNELGROUPS_NONE;
|
||||
manualSettingsData.ChannelNumber[channel] = CHANNEL_NUMBER_NONE;
|
||||
manualSettingsData.FlightModeNumber = DEFAULT_FLIGHT_MODE_NUMBER;
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
}
|
||||
resetFlightModeSettings();
|
||||
}
|
||||
|
||||
void ConfigInputWidget::resetFlightModeSettings()
|
||||
{
|
||||
// Reset FlightMode settings
|
||||
manualSettingsData.FlightModeNumber = DEFAULT_FLIGHT_MODE_NUMBER;
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
for (uint8_t pos = 0; pos < FlightModeSettings::FLIGHTMODEPOSITION_NUMELEM; pos++) {
|
||||
flightModeSignalValue[pos] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigInputWidget::resetActuatorSettings()
|
||||
|
@ -115,6 +115,8 @@ private:
|
||||
QList<int> acroChannelOrder;
|
||||
QList<int> groundChannelOrder;
|
||||
|
||||
uint16_t flightModeSignalValue[FlightModeSettings::FLIGHTMODEPOSITION_NUMELEM];
|
||||
|
||||
UAVObject::Metadata manualControlMdata;
|
||||
ManualControlCommand *manualCommandObj;
|
||||
ManualControlCommand::DataFields manualCommandData;
|
||||
@ -161,6 +163,8 @@ private:
|
||||
QGraphicsSvgItem *m_txAccess2;
|
||||
QGraphicsSvgItem *m_txAccess3;
|
||||
QGraphicsSvgItem *m_txFlightMode;
|
||||
QGraphicsSvgItem *m_txFlightModeCountBG;
|
||||
QGraphicsSimpleTextItem *m_txFlightModeCountText;
|
||||
QGraphicsSvgItem *m_txBackground;
|
||||
QGraphicsSvgItem *m_txArrows;
|
||||
QTransform m_txLeftStickOrig;
|
||||
@ -172,6 +176,8 @@ private:
|
||||
QTransform m_txFlightModeCOrig;
|
||||
QTransform m_txFlightModeLOrig;
|
||||
QTransform m_txFlightModeROrig;
|
||||
QTransform m_txFlightModeCountBGOrig;
|
||||
QTransform m_txFlightModeCountTextOrig;
|
||||
QTransform m_txMainBodyOrig;
|
||||
QTransform m_txArrowsOrig;
|
||||
QTimer *animate;
|
||||
@ -217,6 +223,7 @@ private slots:
|
||||
void checkThrottleRange();
|
||||
void updateCalibration();
|
||||
void resetChannelSettings();
|
||||
void resetFlightModeSettings();
|
||||
void resetActuatorSettings();
|
||||
void forceOneFlightMode();
|
||||
|
||||
|
@ -246,10 +246,14 @@ void ConfigRevoWidget::storeAndClearBoardRotation()
|
||||
AuxMagSettings *auxMagSettings = AuxMagSettings::GetInstance(getObjectManager());
|
||||
Q_ASSERT(auxMagSettings);
|
||||
AuxMagSettings::DataFields auxMagData = auxMagSettings->getData();
|
||||
auxMagStoredBoardRotation = auxMagData.Orientation;
|
||||
auxMagStoredBoardRotation[AuxMagSettings::BOARDROTATION_YAW] = auxMagData.BoardRotation[AuxMagSettings::BOARDROTATION_YAW];
|
||||
auxMagStoredBoardRotation[AuxMagSettings::BOARDROTATION_ROLL] = auxMagData.BoardRotation[AuxMagSettings::BOARDROTATION_ROLL];
|
||||
auxMagStoredBoardRotation[AuxMagSettings::BOARDROTATION_PITCH] = auxMagData.BoardRotation[AuxMagSettings::BOARDROTATION_PITCH];
|
||||
|
||||
// Set aux mag board rotation to no rotation
|
||||
auxMagData.Orientation = 0.0f;
|
||||
auxMagData.BoardRotation[AuxMagSettings::BOARDROTATION_YAW] = 0;
|
||||
auxMagData.BoardRotation[AuxMagSettings::BOARDROTATION_ROLL] = 0;
|
||||
auxMagData.BoardRotation[AuxMagSettings::BOARDROTATION_PITCH] = 0;
|
||||
auxMagSettings->setData(auxMagData);
|
||||
}
|
||||
}
|
||||
@ -273,7 +277,9 @@ void ConfigRevoWidget::recallBoardRotation()
|
||||
AuxMagSettings *auxMagSettings = AuxMagSettings::GetInstance(getObjectManager());
|
||||
Q_ASSERT(auxMagSettings);
|
||||
AuxMagSettings::DataFields auxMagData = auxMagSettings->getData();
|
||||
auxMagData.Orientation = auxMagStoredBoardRotation;
|
||||
auxMagData.BoardRotation[AuxMagSettings::BOARDROTATION_YAW] = auxMagStoredBoardRotation[AuxMagSettings::BOARDROTATION_YAW];
|
||||
auxMagData.BoardRotation[AuxMagSettings::BOARDROTATION_ROLL] = auxMagStoredBoardRotation[AuxMagSettings::BOARDROTATION_ROLL];
|
||||
auxMagData.BoardRotation[AuxMagSettings::BOARDROTATION_PITCH] = auxMagStoredBoardRotation[AuxMagSettings::BOARDROTATION_PITCH];
|
||||
auxMagSettings->setData(auxMagData);
|
||||
}
|
||||
}
|
||||
|
@ -64,7 +64,7 @@ private:
|
||||
|
||||
// Board rotation store/recall for FC and for aux mag
|
||||
qint16 storedBoardRotation[3];
|
||||
float auxMagStoredBoardRotation;
|
||||
qint16 auxMagStoredBoardRotation[3];
|
||||
bool isBoardRotationStored;
|
||||
|
||||
private slots:
|
||||
|
@ -639,6 +639,7 @@ void ConfigStabilizationWidget::onBoardConnected()
|
||||
void ConfigStabilizationWidget::stabBankChanged(int index)
|
||||
{
|
||||
bool dirty = isDirty();
|
||||
disconnect(this, SIGNAL(widgetContentsChanged(QWidget *)), this, SLOT(processLinkedWidgets(QWidget *)));
|
||||
|
||||
updateObjectFromThrottleCurve();
|
||||
foreach(QTabBar * tabBar, m_stabTabBars) {
|
||||
@ -655,6 +656,8 @@ void ConfigStabilizationWidget::stabBankChanged(int index)
|
||||
|
||||
m_currentStabSettingsBank = index;
|
||||
updateThrottleCurveFromObject();
|
||||
|
||||
connect(this, SIGNAL(widgetContentsChanged(QWidget *)), this, SLOT(processLinkedWidgets(QWidget *)));
|
||||
setDirty(dirty);
|
||||
}
|
||||
|
||||
|
@ -419,12 +419,12 @@ void ConfigTxPIDWidget::updateSpinBoxProperties(int selectedPidOption)
|
||||
minPID->setDecimals(0);
|
||||
maxPID->setDecimals(0);
|
||||
} else if (isAcroPlusFactorOption(selectedPidOption)) {
|
||||
minPID->setRange(0, 1);
|
||||
maxPID->setRange(0, 1);
|
||||
minPID->setSingleStep(0.01);
|
||||
maxPID->setSingleStep(0.01);
|
||||
minPID->setDecimals(2);
|
||||
maxPID->setDecimals(2);
|
||||
minPID->setRange(0, 100);
|
||||
maxPID->setRange(0, 100);
|
||||
minPID->setSingleStep(1);
|
||||
maxPID->setSingleStep(1);
|
||||
minPID->setDecimals(0);
|
||||
maxPID->setDecimals(0);
|
||||
} else {
|
||||
minPID->setRange(0, 99.99);
|
||||
maxPID->setRange(0, 99.99);
|
||||
|
File diff suppressed because one or more lines are too long
Before Width: | Height: | Size: 424 KiB After Width: | Height: | Size: 452 KiB |
@ -12,7 +12,6 @@ InputChannelForm::InputChannelForm(const int index, QWidget *parent) :
|
||||
connect(ui->channelMin, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated()));
|
||||
connect(ui->channelMax, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated()));
|
||||
connect(ui->neutralValue, SIGNAL(valueChanged(int)), this, SLOT(neutralUpdated()));
|
||||
connect(ui->channelNeutral, SIGNAL(valueChanged(int)), this, SLOT(updateTooltip()));
|
||||
connect(ui->channelGroup, SIGNAL(currentIndexChanged(int)), this, SLOT(groupUpdated()));
|
||||
connect(ui->channelRev, SIGNAL(toggled(bool)), this, SLOT(reversedUpdated()));
|
||||
|
||||
@ -58,13 +57,6 @@ void InputChannelForm::minMaxUpdated()
|
||||
updateNeutralMark();
|
||||
}
|
||||
|
||||
void InputChannelForm::updateTooltip()
|
||||
{
|
||||
int currentValue = ui->channelNeutral->value();
|
||||
|
||||
ui->channelNeutral->setToolTip(QString::number(currentValue));
|
||||
}
|
||||
|
||||
void InputChannelForm::neutralUpdated()
|
||||
{
|
||||
int neutralValue = ui->neutralValue->value();
|
||||
@ -98,13 +90,17 @@ void InputChannelForm::updateNeutralMark()
|
||||
float neutralPosition = offset / range;
|
||||
|
||||
ui->channelNeutral->setStyleSheet(
|
||||
"QSlider::groove:horizontal { border: 1px solid rgb(196, 196, 196); height: 6px; border-radius: 2px; "
|
||||
"QSlider::groove:horizontal { border: 1px solid rgb(196, 196, 196); margin: 0px 23px 0px 23px; height: 6px; border-radius: 2px; "
|
||||
"background: qlineargradient(x1:0, y1:0, x2:1, y2:0, stop:" + QString::number(neutralPosition - 0.01) + " transparent, stop:"
|
||||
+ QString::number(neutralPosition) + " red, stop:" + QString::number(neutralPosition + 0.01) + " transparent); }"
|
||||
"QSlider::add-page:horizontal { background: rgba(255,255,255,180); border: 1px solid #777; margin: 0px 0px 0px 2px; border-radius: 4px; }"
|
||||
"QSlider::sub-page:horizontal { background: rgba(78,147,246,180); border: 1px solid #777; margin: 0px 2px 0px 0px; border-radius: 4px; }"
|
||||
"QSlider::handle:horizontal { background: rgba(196,196,196,180); width: 18px; height: 28px; margin: -2px 0px; border-radius: 3px; "
|
||||
"border: 1px solid #777; }"
|
||||
"QSlider::add-page:horizontal { background: rgba(255,255,255,120); border: 1px solid #777; margin: 0px 23px 0px 2px; border-radius: 4px; }"
|
||||
"QSlider::sub-page:horizontal { background: rgba(78,147,246,120); border: 1px solid #777; margin: 0px 2px 0px 23px; border-radius: 4px; }"
|
||||
|
||||
"QSlider::handle:horizontal { background: qlineargradient(x1:0, y1:0, x2:1, y2:0, "
|
||||
"stop: 0 rgba(196, 196, 196, 180), stop: 0.45 rgba(196, 196, 196, 180), "
|
||||
"stop: 0.46 rgba(255,0,0,100), stop: 0.54 rgba(255,0,0,100), "
|
||||
"stop: 0.55 rgba(196, 196, 196, 180), stop: 1 rgba(196, 196, 196, 180)); "
|
||||
"width: 46px; height: 28px; margin: -6px -23px -6px -23px; border-radius: 6px; border: 1px solid #777; }"
|
||||
);
|
||||
}
|
||||
|
||||
|
@ -24,7 +24,6 @@ public:
|
||||
|
||||
private slots:
|
||||
void updateNeutralMark();
|
||||
void updateTooltip();
|
||||
void minMaxUpdated();
|
||||
void neutralUpdated();
|
||||
void reversedUpdated();
|
||||
|
@ -6,8 +6,8 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>923</width>
|
||||
<height>57</height>
|
||||
<width>993</width>
|
||||
<height>100</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
@ -141,7 +141,7 @@ margin:1px;</string>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>110</width>
|
||||
<width>120</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
@ -169,7 +169,7 @@ margin:1px;</string>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
@ -737,7 +737,7 @@ margin:1px;</string>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="5">
|
||||
<widget class="QSlider" name="channelNeutral">
|
||||
<widget class="TextBubbleSlider" name="channelNeutral">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
@ -746,13 +746,16 @@ margin:1px;</string>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<width>200</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Channel input value (µs)</string>
|
||||
</property>
|
||||
<property name="accessibleName">
|
||||
<string/>
|
||||
</property>
|
||||
@ -841,6 +844,20 @@ margin:1px;</string>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<customwidgets>
|
||||
<customwidget>
|
||||
<class>TextBubbleSlider</class>
|
||||
<extends>QSlider</extends>
|
||||
<header>utils/textbubbleslider.h</header>
|
||||
</customwidget>
|
||||
</customwidgets>
|
||||
<tabstops>
|
||||
<tabstop>channelGroup</tabstop>
|
||||
<tabstop>channelNumber</tabstop>
|
||||
<tabstop>channelMin</tabstop>
|
||||
<tabstop>channelNeutral</tabstop>
|
||||
<tabstop>channelMax</tabstop>
|
||||
</tabstops>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
||||
|
@ -1,5 +0,0 @@
|
||||
<RCC>
|
||||
<qresource prefix="/pfdqml">
|
||||
<file>fonts/PTS75F.ttf</file>
|
||||
</qresource>
|
||||
</RCC>
|
@ -28,5 +28,3 @@ SOURCES += \
|
||||
OTHER_FILES += PfdQml.pluginspec
|
||||
|
||||
FORMS += pfdqmlgadgetoptionspage.ui
|
||||
|
||||
RESOURCES += PfdResources.qrc
|
||||
|
@ -234,6 +234,9 @@ void ConnectionDiagram::setupGraphicsScene()
|
||||
case VehicleConfigurationSource::GPS_UBX:
|
||||
elementsToShow << QString("%1OPGPS-v8-ublox").arg(prefix);
|
||||
break;
|
||||
case VehicleConfigurationSource::GPS_UBX_FLEXI_I2CMAG:
|
||||
elementsToShow << QString("%1generic-ublox-mag").arg(prefix);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
@ -40,8 +40,10 @@ void AirSpeedPage::initializePage(VehicleConfigurationSource *settings)
|
||||
// Enable all
|
||||
setItemDisabled(-1, false);
|
||||
if (settings->getInputType() == VehicleConfigurationSource::INPUT_SBUS ||
|
||||
settings->getInputType() == VehicleConfigurationSource::INPUT_DSM) {
|
||||
// Disable non estimated sensors if ports are taken by receivers
|
||||
settings->getInputType() == VehicleConfigurationSource::INPUT_DSM ||
|
||||
settings->getInputType() == VehicleConfigurationSource::INPUT_SRXL ||
|
||||
settings->getGpsType() == VehicleConfigurationSource::GPS_UBX_FLEXI_I2CMAG) {
|
||||
// Disable non estimated sensors if ports are taken by receivers or I2C Mag
|
||||
setItemDisabled(VehicleConfigurationSource::AIRSPEED_EAGLETREE, true);
|
||||
setItemDisabled(VehicleConfigurationSource::AIRSPEED_MS4525, true);
|
||||
if (getSelectedItem()->id() == VehicleConfigurationSource::AIRSPEED_EAGLETREE ||
|
||||
|
@ -37,7 +37,18 @@ GpsPage::~GpsPage()
|
||||
|
||||
void GpsPage::initializePage(VehicleConfigurationSource *settings)
|
||||
{
|
||||
Q_UNUSED(settings);
|
||||
// Enable all
|
||||
setItemDisabled(-1, false);
|
||||
if (settings->getInputType() == VehicleConfigurationSource::INPUT_SBUS ||
|
||||
settings->getInputType() == VehicleConfigurationSource::INPUT_DSM ||
|
||||
settings->getInputType() == VehicleConfigurationSource::INPUT_SRXL) {
|
||||
// Disable GPS+I2C Mag
|
||||
setItemDisabled(VehicleConfigurationSource::GPS_UBX_FLEXI_I2CMAG, true);
|
||||
if (getSelectedItem()->id() == VehicleConfigurationSource::GPS_UBX_FLEXI_I2CMAG) {
|
||||
// If previously selected invalid GPS, reset to no GPS
|
||||
setSelectedItem(VehicleConfigurationSource::GPS_DISABLED);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool GpsPage::validatePage(SelectionItem *selectedItem)
|
||||
@ -70,6 +81,12 @@ void GpsPage::setupSelection(Selection *selection)
|
||||
"OPGPS-v9",
|
||||
SetupWizard::GPS_PLATINUM);
|
||||
|
||||
selection->addItem(tr("U-Blox Based + Magnetometer"),
|
||||
tr("Select this option for the generic U-Blox chipset based GPS + I2C Magnetometer.\n\n"
|
||||
"GPS is connected to MainPort and two wires I2C to FlexiPort."),
|
||||
"generic-ublox-mag",
|
||||
SetupWizard::GPS_UBX_FLEXI_I2CMAG);
|
||||
|
||||
selection->addItem(tr("U-Blox Based"),
|
||||
tr("Select this option for the OpenPilot V8 GPS or generic U-Blox chipset based GPS."),
|
||||
"OPGPS-v8-ublox",
|
||||
|
File diff suppressed because one or more lines are too long
Before Width: | Height: | Size: 3.0 MiB After Width: | Height: | Size: 3.0 MiB |
File diff suppressed because one or more lines are too long
Before Width: | Height: | Size: 424 KiB After Width: | Height: | Size: 485 KiB |
@ -377,6 +377,9 @@ QString SetupWizard::getSummaryText()
|
||||
case INPUT_DSM:
|
||||
summary.append(tr("Spektrum Satellite"));
|
||||
break;
|
||||
case INPUT_SRXL:
|
||||
summary.append(tr("Multiplex SRXL"));
|
||||
break;
|
||||
default:
|
||||
summary.append(tr("Unknown"));
|
||||
}
|
||||
@ -425,6 +428,9 @@ QString SetupWizard::getSummaryText()
|
||||
case GPS_PLATINUM:
|
||||
summary.append(tr("OpenPilot Platinum"));
|
||||
break;
|
||||
case GPS_UBX_FLEXI_I2CMAG:
|
||||
summary.append(tr("Generic UBLOX + I2C Magnetometer"));
|
||||
break;
|
||||
case GPS_UBX:
|
||||
summary.append(tr("OpenPilot v8 or Generic UBLOX GPS"));
|
||||
break;
|
||||
|
@ -159,13 +159,16 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
|
||||
}
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_SBUS:
|
||||
// We have to set teletry on flexport since s.bus needs the mainport.
|
||||
// We have to set teletry on flexiport since s.bus needs the mainport.
|
||||
data.CC_MainPort = HwSettings::CC_MAINPORT_SBUS;
|
||||
data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_TELEMETRY;
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_DSM:
|
||||
data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_DSM;
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_SRXL:
|
||||
data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_SRXL;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
@ -193,7 +196,7 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_SBUS:
|
||||
data.RM_MainPort = HwSettings::RM_MAINPORT_SBUS;
|
||||
// We have to set telemetry on flexport since s.bus needs the mainport on all but Revo.
|
||||
// We have to set telemetry on flexiport since s.bus needs the mainport on all but Revo.
|
||||
if (m_configSource->getControllerType() != VehicleConfigurationSource::CONTROLLER_REVO) {
|
||||
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_TELEMETRY;
|
||||
}
|
||||
@ -238,11 +241,26 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
|
||||
AuxMagSettings *magSettings = AuxMagSettings::GetInstance(m_uavoManager);
|
||||
Q_ASSERT(magSettings);
|
||||
AuxMagSettings::DataFields magsData = magSettings->getData();
|
||||
magsData.Type = AuxMagSettings::TYPE_GPSV9;
|
||||
magsData.Usage = AuxMagSettings::USAGE_AUXONLY;
|
||||
magSettings->setData(magsData);
|
||||
addModifiedObject(magSettings, tr("Writing External Mag sensor settings"));
|
||||
break;
|
||||
}
|
||||
case VehicleConfigurationSource::GPS_UBX_FLEXI_I2CMAG:
|
||||
{
|
||||
gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_UBX;
|
||||
gpsData.UbxAutoConfig = GPSSettings::UBXAUTOCONFIG_AUTOBAUDANDCONFIGURE;
|
||||
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_I2C;
|
||||
AuxMagSettings *magSettings = AuxMagSettings::GetInstance(m_uavoManager);
|
||||
Q_ASSERT(magSettings);
|
||||
AuxMagSettings::DataFields magsData = magSettings->getData();
|
||||
magsData.Type = AuxMagSettings::TYPE_FLEXI;
|
||||
magsData.Usage = AuxMagSettings::USAGE_AUXONLY;
|
||||
magSettings->setData(magsData);
|
||||
addModifiedObject(magSettings, tr("Writing I2C Mag sensor settings"));
|
||||
}
|
||||
|
||||
case VehicleConfigurationSource::GPS_DISABLED:
|
||||
// Should not be able to reach here
|
||||
break;
|
||||
|
@ -68,7 +68,7 @@ public:
|
||||
enum SERVO_TYPE { SERVO_ANALOG, SERVO_DIGITAL, SERVO_UNKNOWN };
|
||||
enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSM, INPUT_SRXL, INPUT_UNKNOWN };
|
||||
enum AIRSPEED_TYPE { AIRSPEED_ESTIMATE, AIRSPEED_EAGLETREE, AIRSPEED_MS4525, AIRSPEED_DISABLED };
|
||||
enum GPS_TYPE { GPS_PLATINUM, GPS_UBX, GPS_NMEA, GPS_DISABLED };
|
||||
enum GPS_TYPE { GPS_PLATINUM, GPS_UBX_FLEXI_I2CMAG, GPS_UBX, GPS_NMEA, GPS_DISABLED };
|
||||
enum RADIO_SETTING { RADIO_TELEMETRY, RADIO_DISABLED };
|
||||
|
||||
virtual VehicleConfigurationSource::CONTROLLER_TYPE getControllerType() const = 0;
|
||||
|
@ -74,7 +74,7 @@ WelcomeMode::WelcomeMode() :
|
||||
// This will delete the network access manager instance when we're done
|
||||
connect(networkAccessManager, SIGNAL(finished(QNetworkReply *)), networkAccessManager, SLOT(deleteLater()));
|
||||
|
||||
networkAccessManager->get(QNetworkRequest(QUrl("https://github.com/librepilot/LibrePilot/raw/master/.STABLEVER")));
|
||||
networkAccessManager->get(QNetworkRequest(QUrl("http://www.librepilot.org/stable-version")));
|
||||
} else {
|
||||
// No network, can delete this now as we don't need it.
|
||||
delete networkAccessManager;
|
||||
|
@ -27,7 +27,7 @@ Rectangle {
|
||||
|
||||
FontLoader {
|
||||
id: pt_bold
|
||||
source: "qrc:/pfdqml/fonts/PTS75F.ttf"
|
||||
source: "qrc:/utils/fonts/PTS75F.ttf"
|
||||
}
|
||||
|
||||
width: Math.floor((parent.paintedHeight * 1.32) - (parent.paintedHeight * 0.013))
|
||||
|
@ -2,4 +2,4 @@
|
||||
|
||||
* Release from upstream Git repository
|
||||
|
||||
-- James Duley <james@openpilot.org> <DATE>
|
||||
-- The LibrePilot Project <<EMAIL>> <DATE>
|
||||
|
@ -249,9 +249,9 @@ Section "Shortcuts" InSecShortcuts
|
||||
"" "$INSTDIR\bin\${GCS_SMALL_NAME}.exe" 0
|
||||
CreateShortCut "$SMPROGRAMS\${ORG_BIG_NAME}\Website.lnk" "http://www.librepilot.org" \
|
||||
"" "$INSTDIR\bin\${GCS_SMALL_NAME}.exe" 0
|
||||
CreateShortCut "$SMPROGRAMS\${ORG_BIG_NAME}\Wiki.lnk" "http://wiki.openpilot.org" \
|
||||
CreateShortCut "$SMPROGRAMS\${ORG_BIG_NAME}\Wiki.lnk" "https://librepilot.atlassian.net/wiki/display/LPDOC/LibrePilot+Documentation" \
|
||||
"" "$INSTDIR\bin\${GCS_SMALL_NAME}.exe" 0
|
||||
CreateShortCut "$SMPROGRAMS\${ORG_BIG_NAME}\Forums.lnk" "http://forums.librepilot.org" \
|
||||
CreateShortCut "$SMPROGRAMS\${ORG_BIG_NAME}\Forums.lnk" "http://forum.librepilot.org" \
|
||||
"" "$INSTDIR\bin\${GCS_SMALL_NAME}.exe" 0
|
||||
CreateShortCut "$DESKTOP\${GCS_BIG_NAME}.lnk" "$INSTDIR\bin\${GCS_SMALL_NAME}.exe" \
|
||||
"" "$INSTDIR\bin\${GCS_SMALL_NAME}.exe" 0 "" "" "${PRODUCT_NAME} ${PRODUCT_VERSION}. ${BUILD_DESCRIPTION}"
|
||||
@ -268,7 +268,7 @@ Section ; create uninstall info
|
||||
WriteRegStr HKCU "Software\Microsoft\Windows\CurrentVersion\Uninstall\${ORG_BIG_NAME}" "DisplayIcon" '"$INSTDIR\bin\${GCS_SMALL_NAME}.exe"'
|
||||
WriteRegStr HKCU "Software\Microsoft\Windows\CurrentVersion\Uninstall\${ORG_BIG_NAME}" "Publisher" "LibrePilot Team"
|
||||
WriteRegStr HKCU "Software\Microsoft\Windows\CurrentVersion\Uninstall\${ORG_BIG_NAME}" "URLInfoAbout" "http://www.librepilot.org"
|
||||
WriteRegStr HKCU "Software\Microsoft\Windows\CurrentVersion\Uninstall\${ORG_BIG_NAME}" "HelpLink" "http://wiki.openpilot.org"
|
||||
WriteRegStr HKCU "Software\Microsoft\Windows\CurrentVersion\Uninstall\${ORG_BIG_NAME}" "HelpLink" "https://librepilot.atlassian.net/wiki/display/LPDOC/LibrePilot+Documentation"
|
||||
WriteRegDWORD HKCU "Software\Microsoft\Windows\CurrentVersion\Uninstall\${ORG_BIG_NAME}" "EstimatedSize" 100600
|
||||
WriteRegDWORD HKCU "Software\Microsoft\Windows\CurrentVersion\Uninstall\${ORG_BIG_NAME}" "NoModify" 1
|
||||
WriteRegDWORD HKCU "Software\Microsoft\Windows\CurrentVersion\Uninstall\${ORG_BIG_NAME}" "NoRepair" 1
|
||||
|
@ -5,8 +5,8 @@
|
||||
<field name="mag_transform" units="gain" type="float" elementnames="r0c0,r0c1,r0c2,r1c0,r1c1,r1c2,r2c0,r2c1,r2c2"
|
||||
defaultvalue="1,0,0,0,1,0,0,0,1"/>
|
||||
<field name="MagBiasNullingRate" units="" type="float" elements="1" defaultvalue="0"/>
|
||||
<field name="Orientation" units="degrees" type="float" elements="1" defaultvalue="0"/>
|
||||
<field name="Type" units="" type="enum" elements="1" options="GPSV9,Ext" defaultvalue="GPSV9"/>
|
||||
<field name="BoardRotation" units="deg" type="int16" elementnames="Roll,Pitch,Yaw" defaultvalue="0,0,0"/>
|
||||
<field name="Type" units="" type="enum" elements="1" options="GPSV9,Ext,Flexi" defaultvalue="GPSV9"/>
|
||||
<field name="Usage" units="" type="enum" elements="1" options="Both,OnboardOnly,AuxOnly" defaultvalue="Both"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user