mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Rover: always specify rangefinder instance
This commit is contained in:
parent
87df06c45f
commit
f29fe8bb88
@ -142,7 +142,7 @@ private:
|
||||
AP_Baro barometer;
|
||||
Compass compass;
|
||||
AP_InertialSensor ins;
|
||||
RangeFinder sonar { serial_manager };
|
||||
RangeFinder sonar { serial_manager, ROTATION_NONE };
|
||||
AP_Button button;
|
||||
|
||||
// flight modes convenience array
|
||||
|
@ -56,7 +56,7 @@ void Rover::read_sonars(void)
|
||||
{
|
||||
sonar.update();
|
||||
|
||||
if (sonar.status() == RangeFinder::RangeFinder_NotConnected) {
|
||||
if (sonar.status(0) == RangeFinder::RangeFinder_NotConnected) {
|
||||
// this makes it possible to disable sonar at runtime
|
||||
return;
|
||||
}
|
||||
@ -214,7 +214,7 @@ void Rover::update_sensor_status_flags(void)
|
||||
if (g.sonar_trigger_cm > 0) {
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||
}
|
||||
if (sonar.has_data()) {
|
||||
if (sonar.has_data(0)) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||
}
|
||||
}
|
||||
|
@ -365,7 +365,7 @@ int8_t Rover::test_sonar(uint8_t argc, const Menu::arg *argv)
|
||||
delay(20);
|
||||
sonar.update();
|
||||
|
||||
if (sonar.status() == RangeFinder::RangeFinder_NotConnected) {
|
||||
if (sonar.status(0) == RangeFinder::RangeFinder_NotConnected && sonar.status(1) == RangeFinder::RangeFinder_NotConnected) {
|
||||
cliSerial->printf("WARNING: Sonar is not enabled\n");
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user