mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 14:47:44 +08:00
MPU6K: Fix device ID
This commit is contained in:
@@ -1833,8 +1833,8 @@ MPU6500::measure()
|
||||
arb.temperature_raw = report.temp;
|
||||
arb.temperature = _last_temperature;
|
||||
|
||||
/* Return class instance as a surrogate device ID */
|
||||
arb.device_id = _accel_class_instance;
|
||||
/* return device ID */
|
||||
arb.device_id = _device_id;
|
||||
|
||||
grb.x_raw = report.gyro_x;
|
||||
grb.y_raw = report.gyro_y;
|
||||
@@ -1869,9 +1869,8 @@ MPU6500::measure()
|
||||
grb.temperature_raw = report.temp;
|
||||
grb.temperature = _last_temperature;
|
||||
|
||||
/* Use class instance as a surrogate hardware ID */
|
||||
grb.device_id = _gyro->_gyro_class_instance;
|
||||
grb.device_id = 0;
|
||||
/* return device ID */
|
||||
grb.device_id = _gyro->_device_id;
|
||||
|
||||
_accel_reports->force(&arb);
|
||||
_gyro_reports->force(&grb);
|
||||
@@ -2091,7 +2090,7 @@ start(bool external_bus, enum Rotation rotation, int range)
|
||||
fail:
|
||||
|
||||
if (*g_dev_ptr != nullptr) {
|
||||
delete(*g_dev_ptr);
|
||||
delete *g_dev_ptr;
|
||||
*g_dev_ptr = nullptr;
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user