mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: Fix name of sensor
This commit is contained in:
parent
cbbc4d6774
commit
a4d0ad8571
|
@ -375,7 +375,7 @@ bool AP_InertialSensor_MPU9250::_data_ready(uint8_t int_status)
|
|||
}
|
||||
|
||||
/*
|
||||
* Timer process to poll for new data from the MPU6000.
|
||||
* Timer process to poll for new data from the MPU9250.
|
||||
*/
|
||||
void AP_InertialSensor_MPU9250::_poll_data()
|
||||
{
|
||||
|
@ -454,7 +454,7 @@ void AP_InertialSensor_MPU9250::_register_write(uint8_t reg, uint8_t val)
|
|||
bool AP_InertialSensor_MPU9250::_hardware_init(void)
|
||||
{
|
||||
if (!_dev->get_semaphore()->take(100)) {
|
||||
AP_HAL::panic("MPU6000: Unable to get semaphore");
|
||||
AP_HAL::panic("MPU9250: Unable to get semaphore");
|
||||
}
|
||||
|
||||
// initially run the bus at low speed
|
||||
|
|
Loading…
Reference in New Issue