forked from Archive/PX4-Autopilot
stop manually defining physical constants
This commit is contained in:
parent
7538ea44e3
commit
d75fd72c02
|
@ -44,6 +44,7 @@
|
|||
#include <float.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <ecl/geo/geo.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
|
@ -555,7 +556,7 @@ BATT_SMBUS::cycle()
|
|||
|
||||
// read battery temperature and covert to Celsius
|
||||
if (read_reg(BATT_SMBUS_TEMP, tmp) == OK) {
|
||||
new_report.temperature = (float)(((float)tmp / 10.0f) - 273.15f);
|
||||
new_report.temperature = (float)(((float)tmp / 10.0f) + CONSTANTS_ABSOLUTE_NULL_CELSIUS);
|
||||
}
|
||||
|
||||
//Check if remaining % is out of range
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <ecl/geo/geo.h>
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
@ -171,8 +171,6 @@
|
|||
#define ADIS16448_ACCEL_MAX_OUTPUT_RATE 1221
|
||||
#define ADIS16448_GYRO_MAX_OUTPUT_RATE 1221
|
||||
|
||||
#define ADIS16448_ONE_G 9.80665f
|
||||
|
||||
#define FW_FILTER false
|
||||
|
||||
#define SPI_BUS_SPEED 1000000
|
||||
|
@ -733,8 +731,8 @@ int ADIS16448::reset()
|
|||
/* Set IMU sample rate */
|
||||
_set_sample_rate(_sample_rate);
|
||||
|
||||
_accel_range_scale = ADIS16448_ONE_G * ACCELINITIALSENSITIVITY;
|
||||
_accel_range_m_s2 = ADIS16448_ONE_G * ACCELDYNAMICRANGE;
|
||||
_accel_range_scale = CONSTANTS_ONE_G * ACCELINITIALSENSITIVITY;
|
||||
_accel_range_m_s2 = CONSTANTS_ONE_G * ACCELDYNAMICRANGE;
|
||||
_mag_range_scale = MAGINITIALSENSITIVITY;
|
||||
_mag_range_mgauss = MAGDYNAMICRANGE;
|
||||
|
||||
|
@ -1140,7 +1138,7 @@ ADIS16448::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
return -EINVAL;
|
||||
|
||||
case ACCELIOCGRANGE:
|
||||
return (unsigned long)((_accel_range_m_s2) / ADIS16448_ONE_G + 0.5f);
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
|
|
@ -38,6 +38,7 @@
|
|||
|
||||
#include <px4_config.h>
|
||||
#include <px4_defines.h>
|
||||
#include <ecl/geo/geo.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
@ -575,7 +576,7 @@ BMA180::set_range(unsigned max_g)
|
|||
}
|
||||
|
||||
/* set new range scaling factor */
|
||||
_accel_range_m_s2 = _current_range * 9.80665f;
|
||||
_accel_range_m_s2 = _current_range * CONSTANTS_ONE_G;
|
||||
_accel_range_scale = _accel_range_m_s2 / 8192.0f;
|
||||
|
||||
/* enable writing to chip config */
|
||||
|
|
|
@ -239,8 +239,6 @@
|
|||
|
||||
#define BMI055_GYRO_DEFAULT_DRIVER_FILTER_FREQ 50
|
||||
|
||||
#define BMI055_ONE_G 9.80665f
|
||||
|
||||
#define BMI055_BUS_SPEED 10*1000*1000
|
||||
|
||||
#define BMI055_TIMER_REDUCTION 200
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
#include "bmi055.hpp"
|
||||
|
||||
#include <ecl/geo/geo.h>
|
||||
|
||||
/*
|
||||
list of registers that will be checked in check_registers(). Note
|
||||
|
@ -463,7 +463,7 @@ BMI055_accel::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
return set_accel_range(arg);
|
||||
|
||||
case ACCELIOCGRANGE:
|
||||
return (unsigned long)((_accel_range_m_s2) / BMI055_ONE_G + 0.5f);
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
@ -535,8 +535,8 @@ BMI055_accel::set_accel_range(unsigned max_g)
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
_accel_range_scale = (BMI055_ONE_G / lsb_per_g);
|
||||
_accel_range_m_s2 = max_accel_g * BMI055_ONE_G;
|
||||
_accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g);
|
||||
_accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G;
|
||||
|
||||
modify_reg(BMI055_ACC_RANGE, clearbits, setbits);
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#include "bmi160.hpp"
|
||||
#include "bmi160_gyro.hpp"
|
||||
|
||||
#include <ecl/geo/geo.h>
|
||||
|
||||
/*
|
||||
list of registers that will be checked in check_registers(). Note
|
||||
|
@ -743,7 +743,7 @@ BMI160::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
return set_accel_range(arg);
|
||||
|
||||
case ACCELIOCGRANGE:
|
||||
return (unsigned long)((_accel_range_m_s2) / BMI160_ONE_G + 0.5f);
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
@ -905,8 +905,8 @@ BMI160::set_accel_range(unsigned max_g)
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
_accel_range_scale = (BMI160_ONE_G / lsb_per_g);
|
||||
_accel_range_m_s2 = max_accel_g * BMI160_ONE_G;
|
||||
_accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g);
|
||||
_accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G;
|
||||
|
||||
modify_reg(BMIREG_ACC_RANGE, clearbits, setbits);
|
||||
|
||||
|
|
|
@ -238,8 +238,6 @@
|
|||
#define BMI160_GYRO_DEFAULT_ONCHIP_FILTER_FREQ 254.6f
|
||||
#define BMI160_GYRO_DEFAULT_DRIVER_FILTER_FREQ 50
|
||||
|
||||
#define BMI160_ONE_G 9.80665f
|
||||
|
||||
#define BMI160_BUS_SPEED 10*1000*1000
|
||||
|
||||
#define BMI160_TIMER_REDUCTION 200
|
||||
|
|
|
@ -39,6 +39,7 @@
|
|||
|
||||
#include <px4_config.h>
|
||||
#include <px4_defines.h>
|
||||
#include <ecl/geo/geo.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
|
@ -137,7 +138,6 @@
|
|||
|
||||
#define FXOS8701C_MAG_DEFAULT_RANGE_GA 12 /* It is fixed at 12 G */
|
||||
#define FXOS8701C_MAG_DEFAULT_RATE 100
|
||||
#define FXOS8701C_ONE_G 9.80665f
|
||||
|
||||
/*
|
||||
we set the timer interrupt to run a bit faster than the desired
|
||||
|
@ -877,7 +877,7 @@ FXOS8701CQ::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
|
||||
case ACCELIOCGRANGE:
|
||||
/* convert to m/s^2 and return rounded in G */
|
||||
return (unsigned long)((_accel_range_m_s2) / FXOS8701C_ONE_G + 0.5f);
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCGSCALE:
|
||||
/* copy scale out */
|
||||
|
@ -1135,8 +1135,8 @@ FXOS8701CQ::accel_set_range(unsigned max_g)
|
|||
max_accel_g = 2;
|
||||
}
|
||||
|
||||
_accel_range_scale = (FXOS8701C_ONE_G / lsb_per_g);
|
||||
_accel_range_m_s2 = max_accel_g * FXOS8701C_ONE_G;
|
||||
_accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g);
|
||||
_accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G;
|
||||
|
||||
|
||||
modify_reg(FXOS8701CQ_XYZ_DATA_CFG, XYZ_DATA_CFG_FS_MASK, setbits);
|
||||
|
|
|
@ -38,6 +38,7 @@
|
|||
|
||||
#include <px4_config.h>
|
||||
#include <px4_defines.h>
|
||||
#include <ecl/geo/geo.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
|
@ -206,8 +207,6 @@
|
|||
#define LSM303D_MAG_DEFAULT_RANGE_GA 2
|
||||
#define LSM303D_MAG_DEFAULT_RATE 100
|
||||
|
||||
#define LSM303D_ONE_G 9.80665f
|
||||
|
||||
/*
|
||||
we set the timer interrupt to run a bit faster than the desired
|
||||
sample rate and then throw away duplicates using the data ready bit.
|
||||
|
@ -946,7 +945,7 @@ LSM303D::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
|
||||
case ACCELIOCGRANGE:
|
||||
/* convert to m/s^2 and return rounded in G */
|
||||
return (unsigned long)((_accel_range_m_s2) / LSM303D_ONE_G + 0.5f);
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCGSCALE:
|
||||
/* copy scale out */
|
||||
|
@ -1178,27 +1177,27 @@ LSM303D::accel_set_range(unsigned max_g)
|
|||
}
|
||||
|
||||
if (max_g <= 2) {
|
||||
_accel_range_m_s2 = 2.0f * LSM303D_ONE_G;
|
||||
_accel_range_m_s2 = 2.0f * CONSTANTS_ONE_G;
|
||||
setbits |= REG2_FULL_SCALE_2G_A;
|
||||
new_scale_g_digit = 0.061e-3f;
|
||||
|
||||
} else if (max_g <= 4) {
|
||||
_accel_range_m_s2 = 4.0f * LSM303D_ONE_G;
|
||||
_accel_range_m_s2 = 4.0f * CONSTANTS_ONE_G;
|
||||
setbits |= REG2_FULL_SCALE_4G_A;
|
||||
new_scale_g_digit = 0.122e-3f;
|
||||
|
||||
} else if (max_g <= 6) {
|
||||
_accel_range_m_s2 = 6.0f * LSM303D_ONE_G;
|
||||
_accel_range_m_s2 = 6.0f * CONSTANTS_ONE_G;
|
||||
setbits |= REG2_FULL_SCALE_6G_A;
|
||||
new_scale_g_digit = 0.183e-3f;
|
||||
|
||||
} else if (max_g <= 8) {
|
||||
_accel_range_m_s2 = 8.0f * LSM303D_ONE_G;
|
||||
_accel_range_m_s2 = 8.0f * CONSTANTS_ONE_G;
|
||||
setbits |= REG2_FULL_SCALE_8G_A;
|
||||
new_scale_g_digit = 0.244e-3f;
|
||||
|
||||
} else if (max_g <= 16) {
|
||||
_accel_range_m_s2 = 16.0f * LSM303D_ONE_G;
|
||||
_accel_range_m_s2 = 16.0f * CONSTANTS_ONE_G;
|
||||
setbits |= REG2_FULL_SCALE_16G_A;
|
||||
new_scale_g_digit = 0.732e-3f;
|
||||
|
||||
|
@ -1206,7 +1205,7 @@ LSM303D::accel_set_range(unsigned max_g)
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
_accel_range_scale = new_scale_g_digit * LSM303D_ONE_G;
|
||||
_accel_range_scale = new_scale_g_digit * CONSTANTS_ONE_G;
|
||||
|
||||
|
||||
modify_reg(ADDR_CTRL_REG2, clearbits, setbits);
|
||||
|
|
|
@ -56,6 +56,7 @@
|
|||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <ecl/geo/geo.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
@ -1505,7 +1506,7 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
return set_accel_range(arg);
|
||||
|
||||
case ACCELIOCGRANGE:
|
||||
return (unsigned long)((_accel_range_m_s2) / MPU6000_ONE_G + 0.5f);
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
@ -1645,8 +1646,8 @@ MPU6000::set_accel_range(unsigned max_g_in)
|
|||
case MPU6000_REV_C4:
|
||||
case MPU6000_REV_C5:
|
||||
write_checked_reg(MPUREG_ACCEL_CONFIG, 1 << 3);
|
||||
_accel_range_scale = (MPU6000_ONE_G / 4096.0f);
|
||||
_accel_range_m_s2 = 8.0f * MPU6000_ONE_G;
|
||||
_accel_range_scale = (CONSTANTS_ONE_G / 4096.0f);
|
||||
_accel_range_m_s2 = 8.0f * CONSTANTS_ONE_G;
|
||||
return OK;
|
||||
}
|
||||
}
|
||||
|
@ -1677,8 +1678,8 @@ MPU6000::set_accel_range(unsigned max_g_in)
|
|||
}
|
||||
|
||||
write_checked_reg(MPUREG_ACCEL_CONFIG, afs_sel << 3);
|
||||
_accel_range_scale = (MPU6000_ONE_G / lsb_per_g);
|
||||
_accel_range_m_s2 = max_accel_g * MPU6000_ONE_G;
|
||||
_accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g);
|
||||
_accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G;
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
|
|
@ -212,8 +212,6 @@
|
|||
|
||||
#define MPU6000_DEFAULT_ONCHIP_FILTER_FREQ 42
|
||||
|
||||
#define MPU6000_ONE_G 9.80665f
|
||||
|
||||
#ifdef PX4_SPI_BUS_EXT
|
||||
#define EXTERNAL_BUS PX4_SPI_BUS_EXT
|
||||
#else
|
||||
|
|
|
@ -42,6 +42,7 @@
|
|||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <ecl/geo/geo.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
@ -918,7 +919,7 @@ MPU9250::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
return set_accel_range(arg);
|
||||
|
||||
case ACCELIOCGRANGE:
|
||||
return (unsigned long)((_accel_range_m_s2) / MPU9250_ONE_G + 0.5f);
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
@ -1086,8 +1087,8 @@ MPU9250::set_accel_range(unsigned max_g_in)
|
|||
}
|
||||
|
||||
write_checked_reg(MPUREG_ACCEL_CONFIG, afs_sel << 3);
|
||||
_accel_range_scale = (MPU9250_ONE_G / lsb_per_g);
|
||||
_accel_range_m_s2 = max_accel_g * MPU9250_ONE_G;
|
||||
_accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g);
|
||||
_accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G;
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
|
|
@ -190,8 +190,6 @@
|
|||
|
||||
#define MPU9250_DEFAULT_ONCHIP_FILTER_FREQ 41
|
||||
|
||||
#define MPU9250_ONE_G 9.80665f
|
||||
|
||||
#define MPUIOCGIS_I2C (unsigned)(DEVIOCGDEVICEID+100)
|
||||
|
||||
|
||||
|
|
|
@ -36,9 +36,9 @@ px4_add_module(
|
|||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
frsky_data.c
|
||||
sPort_data.c
|
||||
frsky_telemetry.c
|
||||
frsky_data.cpp
|
||||
sPort_data.cpp
|
||||
frsky_telemetry.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
|
|
|
@ -47,9 +47,9 @@
|
|||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <arch/math.h>
|
||||
#include <lib/ecl/geo/geo.h>
|
||||
#include <stdbool.h>
|
||||
#include <math.h>
|
||||
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
|
@ -79,8 +79,8 @@ static int sPort_open_uart(const char *uart_name, struct termios *uart_config, s
|
|||
static int set_uart_speed(int uart, struct termios *uart_config, speed_t speed);
|
||||
static void usage(void);
|
||||
static int frsky_telemetry_thread_main(int argc, char *argv[]);
|
||||
__EXPORT int frsky_telemetry_main(int argc, char *argv[]);
|
||||
|
||||
extern "C" __EXPORT int frsky_telemetry_main(int argc, char *argv[]);
|
||||
|
||||
uint16_t get_telemetry_flight_mode(int px4_flight_mode)
|
||||
{
|
|
@ -47,7 +47,8 @@
|
|||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <arch/math.h>
|
||||
#include <math.h>
|
||||
|
||||
#include <lib/ecl/geo/geo.h>
|
||||
|
||||
#include <uORB/topics/battery_status.h>
|
|
@ -1 +1 @@
|
|||
Subproject commit 02e319431b948f660f8548707849489d6c822fad
|
||||
Subproject commit 8678cc42ba6c87b3ae0724af2becb62b71bf6683
|
|
@ -1918,7 +1918,7 @@ FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float airspee
|
|||
if (orb_copy(ORB_ID(sensor_baro), _sensor_baro_sub, &baro) == PX4_OK) {
|
||||
if (PX4_ISFINITE(baro.pressure) && PX4_ISFINITE(_parameters.throttle_alt_scale)) {
|
||||
// scale throttle as a function of sqrt(p0/p) (~ EAS -> TAS at low speeds and altitudes ignoring temperature)
|
||||
const float eas2tas = sqrtf(MSL_PRESSURE_MILLIBAR / baro.pressure);
|
||||
const float eas2tas = sqrtf(CONSTANTS_STD_PRESSURE_MBAR / baro.pressure);
|
||||
const float scale = constrain((eas2tas - 1.0f) * _parameters.throttle_alt_scale + 1.0f, 1.0f, 2.0f);
|
||||
|
||||
throttle_max = constrain(throttle_max * scale, throttle_min, 1.0f);
|
||||
|
|
|
@ -103,8 +103,6 @@ static constexpr float MANUAL_THROTTLE_CLIMBOUT_THRESH =
|
|||
0.85f; ///< a throttle / pitch input above this value leads to the system switching to climbout mode
|
||||
static constexpr float ALTHOLD_EPV_RESET_THRESH = 5.0f;
|
||||
|
||||
static constexpr float MSL_PRESSURE_MILLIBAR = 1013.25f; ///< standard atmospheric pressure in millibar
|
||||
|
||||
using math::constrain;
|
||||
using math::max;
|
||||
using math::min;
|
||||
|
|
|
@ -775,7 +775,7 @@ void BlockLocalPositionEstimator::predict()
|
|||
Vector3f a(_sub_sensor.get().accelerometer_m_s2);
|
||||
// note, bias is removed in dynamics function
|
||||
_u = _R_att * a;
|
||||
_u(U_az) += 9.81f; // add g
|
||||
_u(U_az) += CONSTANTS_ONE_G; // add g
|
||||
|
||||
// update state space based on new states
|
||||
updateSSStates();
|
||||
|
|
|
@ -90,8 +90,6 @@
|
|||
#include "mavlink_main.h"
|
||||
#include "mavlink_command_sender.h"
|
||||
|
||||
static const float mg2ms2 = CONSTANTS_ONE_G / 1000.0f;
|
||||
|
||||
MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
|
||||
_mavlink(parent),
|
||||
_mission_manager(nullptr),
|
||||
|
@ -1922,9 +1920,9 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
|
|||
struct accel_report accel = {};
|
||||
|
||||
accel.timestamp = timestamp;
|
||||
accel.x_raw = imu.xacc / mg2ms2;
|
||||
accel.y_raw = imu.yacc / mg2ms2;
|
||||
accel.z_raw = imu.zacc / mg2ms2;
|
||||
accel.x_raw = imu.xacc / (CONSTANTS_ONE_G / 1000.0f);
|
||||
accel.y_raw = imu.yacc / (CONSTANTS_ONE_G / 1000.0f);
|
||||
accel.z_raw = imu.zacc / (CONSTANTS_ONE_G / 1000.0f);
|
||||
accel.x = imu.xacc;
|
||||
accel.y = imu.yacc;
|
||||
accel.z = imu.zacc;
|
||||
|
|
|
@ -52,11 +52,6 @@ extern "C" __EXPORT hrt_abstime hrt_reset(void);
|
|||
#define SEND_INTERVAL 20
|
||||
#define UDP_PORT 14560
|
||||
|
||||
#define PRESS_GROUND 101325.0f
|
||||
#define DENSITY 1.2041f
|
||||
|
||||
static const float mg2ms2 = CONSTANTS_ONE_G / 1000.0f;
|
||||
|
||||
#ifdef ENABLE_UART_RC_INPUT
|
||||
#ifndef B460800
|
||||
#define B460800 460800
|
||||
|
@ -632,12 +627,12 @@ void Simulator::initializeSensorData()
|
|||
{
|
||||
// write sensor data to memory so that drivers can copy data from there
|
||||
RawMPUData mpu = {};
|
||||
mpu.accel_z = 9.81f;
|
||||
mpu.accel_z = CONSTANTS_ONE_G;
|
||||
|
||||
write_MPU_data(&mpu);
|
||||
|
||||
RawAccelData accel = {};
|
||||
accel.z = 9.81f;
|
||||
accel.z = CONSTANTS_ONE_G;
|
||||
|
||||
write_accel_data(&accel);
|
||||
|
||||
|
@ -1036,9 +1031,9 @@ int Simulator::publish_sensor_topics(mavlink_hil_sensor_t *imu)
|
|||
struct accel_report accel = {};
|
||||
|
||||
accel.timestamp = timestamp;
|
||||
accel.x_raw = imu->xacc / mg2ms2;
|
||||
accel.y_raw = imu->yacc / mg2ms2;
|
||||
accel.z_raw = imu->zacc / mg2ms2;
|
||||
accel.x_raw = imu->xacc / (CONSTANTS_ONE_G / 1000.0f);
|
||||
accel.y_raw = imu->yacc / (CONSTANTS_ONE_G / 1000.0f);
|
||||
accel.z_raw = imu->zacc / (CONSTANTS_ONE_G / 1000.0f);
|
||||
accel.x = imu->xacc;
|
||||
accel.y = imu->yacc;
|
||||
accel.z = imu->zacc;
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
############################################################################
|
||||
|
||||
set(SRCS
|
||||
airspeed.c
|
||||
airspeed.cpp
|
||||
battery.cpp
|
||||
board_serial.c
|
||||
bson/tinybson.c
|
||||
|
|
|
@ -236,7 +236,7 @@ float calc_true_airspeed(float total_pressure, float static_pressure, float temp
|
|||
{
|
||||
float density = get_air_density(static_pressure, temperature_celsius);
|
||||
|
||||
if (density < 0.0001f || !isfinite(density)) {
|
||||
if (density < 0.0001f || !PX4_ISFINITE(density)) {
|
||||
density = CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C;
|
||||
}
|
||||
|
|
@ -71,7 +71,6 @@
|
|||
|
||||
#define ACCELSIM_ACCEL_DEFAULT_RATE 250
|
||||
#define ACCELSIM_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 30
|
||||
#define ACCELSIM_ONE_G 9.80665f
|
||||
|
||||
#define DIR_READ (1<<7)
|
||||
#define DIR_WRITE (0<<7)
|
||||
|
@ -595,7 +594,7 @@ ACCELSIM::devIOCTL(unsigned long cmd, unsigned long arg)
|
|||
|
||||
case ACCELIOCGRANGE:
|
||||
/* convert to m/s^2 and return rounded in G */
|
||||
return (unsigned long)((_accel_range_m_s2) / ACCELSIM_ONE_G + 0.5f);
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCGSCALE:
|
||||
/* copy scale out */
|
||||
|
@ -732,7 +731,7 @@ ACCELSIM::accel_set_range(unsigned max_g)
|
|||
{
|
||||
float new_scale_g_digit = 0.732e-3f;
|
||||
|
||||
_accel_range_scale = new_scale_g_digit * ACCELSIM_ONE_G;
|
||||
_accel_range_scale = new_scale_g_digit * CONSTANTS_ONE_G;
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
|
|
@ -103,8 +103,6 @@ using namespace DriverFramework;
|
|||
|
||||
#define GYROSIM_GYRO_DEFAULT_RATE 400
|
||||
|
||||
#define GYROSIM_ONE_G 9.80665f
|
||||
|
||||
#ifdef PX4_SPI_BUS_EXT
|
||||
#define EXTERNAL_BUS PX4_SPI_BUS_EXT
|
||||
#else
|
||||
|
@ -819,7 +817,7 @@ GYROSIM::devIOCTL(unsigned long cmd, unsigned long arg)
|
|||
return set_accel_range(arg);
|
||||
|
||||
case ACCELIOCGRANGE:
|
||||
return (unsigned long)((_accel_range_m_s2) / GYROSIM_ONE_G + 0.5f);
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
@ -920,8 +918,8 @@ GYROSIM::set_accel_range(unsigned max_g_in)
|
|||
switch (_product) {
|
||||
case GYROSIMES_REV_C4:
|
||||
write_reg(MPUREG_ACCEL_CONFIG, 1 << 3);
|
||||
_accel_range_scale = (GYROSIM_ONE_G / 4096.0f);
|
||||
_accel_range_m_s2 = 8.0f * GYROSIM_ONE_G;
|
||||
_accel_range_scale = (CONSTANTS_ONE_G / 4096.0f);
|
||||
_accel_range_m_s2 = 8.0f * CONSTANTS_ONE_G;
|
||||
return OK;
|
||||
}
|
||||
|
||||
|
@ -951,8 +949,8 @@ GYROSIM::set_accel_range(unsigned max_g_in)
|
|||
}
|
||||
|
||||
write_reg(MPUREG_ACCEL_CONFIG, afs_sel << 3);
|
||||
_accel_range_scale = (GYROSIM_ONE_G / lsb_per_g);
|
||||
_accel_range_m_s2 = max_accel_g * GYROSIM_ONE_G;
|
||||
_accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g);
|
||||
_accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G;
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
@ -1334,7 +1332,7 @@ test()
|
|||
PX4_INFO("acc y: \t%d\traw 0x%0x", (short)a_report.y_raw, (unsigned short)a_report.y_raw);
|
||||
PX4_INFO("acc z: \t%d\traw 0x%0x", (short)a_report.z_raw, (unsigned short)a_report.z_raw);
|
||||
PX4_INFO("acc range: %8.4f m/s^2 (%8.4f g)", (double)a_report.range_m_s2,
|
||||
(double)(a_report.range_m_s2 / GYROSIM_ONE_G));
|
||||
(double)(a_report.range_m_s2 / CONSTANTS_ONE_G));
|
||||
|
||||
/* do a simple demand read */
|
||||
sz = h_gyro.read(&g_report, sizeof(g_report));
|
||||
|
|
Loading…
Reference in New Issue