AP_InertialSensor: fixed merge conflicts with patches from Lucas

This commit is contained in:
Andrew Tridgell 2016-11-05 10:00:31 +11:00
parent 1990aa96e1
commit 9e7e1b2f01
5 changed files with 10 additions and 14 deletions

View File

@ -178,9 +178,9 @@ void AP_InertialSensor_BMI160::start()
_dev->get_semaphore()->give();
_accel_instance = _imu.register_accel(BMI160_ODR_TO_HZ(BMI160_ODR),
_dev->get_id());
_dev->get_bus_id());
_gyro_instance = _imu.register_gyro(BMI160_ODR_TO_HZ(BMI160_ODR),
_dev->get_id());
_dev->get_bus_id());
/* Call _poll_data() at 1kHz */
_dev->register_periodic_callback(1000,

View File

@ -194,8 +194,6 @@ bool AP_InertialSensor_L3G4200D::_init_sensor(void)
L3G4200D_REG_FIFO_CTL_STREAM);
hal.scheduler->delay(1);
_product_id = AP_PRODUCT_ID_L3G4200D;
_dev->get_semaphore()->give();
return true;
@ -206,8 +204,8 @@ bool AP_InertialSensor_L3G4200D::_init_sensor(void)
*/
void AP_InertialSensor_L3G4200D::start(void)
{
_gyro_instance = _imu.register_gyro(800, _dev->get_id());
_accel_instance = _imu.register_accel(800, _dev->get_id());
_gyro_instance = _imu.register_gyro(800, _dev->get_bus_id());
_accel_instance = _imu.register_accel(800, _dev->get_bus_id());
// start the timer process to read samples
_dev->register_periodic_callback(1250, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_L3G4200D::_accumulate, bool));

View File

@ -505,8 +505,8 @@ fail_whoami:
*/
void AP_InertialSensor_LSM9DS0::start(void)
{
_gyro_instance = _imu.register_gyro(760, _dev_gyro->get_id());
_accel_instance = _imu.register_accel(800, _dev_accel->get_id());
_gyro_instance = _imu.register_gyro(760, _dev_gyro->get_bus_id());
_accel_instance = _imu.register_accel(800, _dev_accel->get_bus_id());
set_gyro_orientation(_gyro_instance, _rotation);
set_accel_orientation(_accel_instance, _rotation);

View File

@ -382,10 +382,8 @@ void AP_InertialSensor_MPU6000::start()
_dev->get_semaphore()->give();
// grab the used instances
_gyro_instance = _imu.register_gyro(1000, _dev->get_id() |
(MPU6000_DRIVER_VERSION_GYRO << 16));
_accel_instance = _imu.register_accel(1000, _dev->get_id() |
(MPU6000_DRIVER_VERSION_ACCEL << 16));
_gyro_instance = _imu.register_gyro(1000, _dev->get_bus_id_devtype(MPU6000_DRIVER_VERSION_GYRO));
_accel_instance = _imu.register_accel(1000, _dev->get_bus_id_devtype(MPU6000_DRIVER_VERSION_ACCEL));
// setup sensor rotations from probe()
set_gyro_orientation(_gyro_instance, _rotation);

View File

@ -320,8 +320,8 @@ void AP_InertialSensor_MPU9250::start()
_dev->get_semaphore()->give();
// grab the used instances
_gyro_instance = _imu.register_gyro(DEFAULT_SAMPLE_RATE, _dev->get_id());
_accel_instance = _imu.register_accel(DEFAULT_SAMPLE_RATE, _dev->get_id());
_gyro_instance = _imu.register_gyro(DEFAULT_SAMPLE_RATE, _dev->get_bus_id());
_accel_instance = _imu.register_accel(DEFAULT_SAMPLE_RATE, _dev->get_bus_id());
// start the timer process to read samples
_dev->register_periodic_callback(1000, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_MPU9250::_read_sample, bool));