mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-16 15:57:35 +08:00
move IMU integration out of drivers to sensors hub to handle accel/gyro sync
- IMU integration move from drivers (PX4Accelerometer/PX4Gyroscope) to sensors/vehicle_imu - sensors: voted_sensors_update now consumes vehicle_imu - delete sensor_accel_integrated, sensor_gyro_integrated - merge sensor_accel_status/sensor_gyro_status into vehicle_imu_status - sensors status output minor improvements (ordering, whitespace, show selected sensor device id and instance)
This commit is contained in:
@@ -128,7 +128,7 @@ int simulator_main(int argc, char *argv[])
|
||||
|
||||
g_sim_task = px4_task_spawn_cmd("simulator",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
SCHED_PRIORITY_MAX,
|
||||
1500,
|
||||
Simulator::start,
|
||||
argv);
|
||||
|
||||
@@ -135,9 +135,6 @@ public:
|
||||
private:
|
||||
Simulator() : ModuleParams(nullptr)
|
||||
{
|
||||
// current default
|
||||
_px4_accel.set_update_rate(250);
|
||||
_px4_gyro.set_update_rate(250);
|
||||
}
|
||||
|
||||
~Simulator()
|
||||
@@ -162,8 +159,8 @@ private:
|
||||
static Simulator *_instance;
|
||||
|
||||
// simulated sensor instances
|
||||
PX4Accelerometer _px4_accel{1311244, ORB_PRIO_DEFAULT, ROTATION_NONE}; // 1311244: DRV_ACC_DEVTYPE_ACCELSIM, BUS: 1, ADDR: 1, TYPE: SIMULATION
|
||||
PX4Gyroscope _px4_gyro{2294028, ORB_PRIO_DEFAULT, ROTATION_NONE}; // 2294028: DRV_GYR_DEVTYPE_GYROSIM, BUS: 1, ADDR: 2, TYPE: SIMULATION
|
||||
PX4Accelerometer _px4_accel{1311244, ORB_PRIO_DEFAULT, ROTATION_NONE}; // 1311244: DRV_IMU_DEVTYPE_SIM, BUS: 1, ADDR: 1, TYPE: SIMULATION
|
||||
PX4Gyroscope _px4_gyro{1311244, ORB_PRIO_DEFAULT, ROTATION_NONE}; // 1311244: DRV_IMU_DEVTYPE_SIM, BUS: 1, ADDR: 1, TYPE: SIMULATION
|
||||
PX4Magnetometer _px4_mag{197388, ORB_PRIO_DEFAULT, ROTATION_NONE}; // 197388: DRV_MAG_DEVTYPE_MAGSIM, BUS: 3, ADDR: 1, TYPE: SIMULATION
|
||||
PX4Barometer _px4_baro{6620172, ORB_PRIO_DEFAULT}; // 6620172: DRV_BARO_DEVTYPE_BAROSIM, BUS: 1, ADDR: 4, TYPE: SIMULATION
|
||||
|
||||
|
||||
@@ -205,16 +205,16 @@ void Simulator::update_sensors(const hrt_abstime &time, const mavlink_hil_sensor
|
||||
}
|
||||
}
|
||||
|
||||
// gyro
|
||||
if ((sensors.fields_updated & SensorSource::GYRO) == SensorSource::GYRO && !_param_sim_gyro_block.get()) {
|
||||
_px4_gyro.update(time, sensors.xgyro, sensors.ygyro, sensors.zgyro);
|
||||
}
|
||||
|
||||
// accel
|
||||
if ((sensors.fields_updated & SensorSource::ACCEL) == SensorSource::ACCEL && !_param_sim_accel_block.get()) {
|
||||
_px4_accel.update(time, sensors.xacc, sensors.yacc, sensors.zacc);
|
||||
}
|
||||
|
||||
// gyro
|
||||
if ((sensors.fields_updated & SensorSource::GYRO) == SensorSource::GYRO && !_param_sim_gyro_block.get()) {
|
||||
_px4_gyro.update(time, sensors.xgyro, sensors.ygyro, sensors.zgyro);
|
||||
}
|
||||
|
||||
// magnetometer
|
||||
if ((sensors.fields_updated & SensorSource::MAG) == SensorSource::MAG && !_param_sim_mag_block.get()) {
|
||||
_px4_mag.update(time, sensors.xmag, sensors.ymag, sensors.zmag);
|
||||
|
||||
Reference in New Issue
Block a user