mirror of https://github.com/ArduPilot/ardupilot
Rover: tidy setting of sensor status flags
This commit is contained in:
parent
ed4dcea57a
commit
d9144ab47c
|
@ -27,15 +27,7 @@ bool GCS_Rover::supersimple_input_active() const
|
||||||
|
|
||||||
void GCS_Rover::update_vehicle_sensor_status_flags(void)
|
void GCS_Rover::update_vehicle_sensor_status_flags(void)
|
||||||
{
|
{
|
||||||
// first what sensors/controllers we have
|
// mode-specific:
|
||||||
#if HAL_PROXIMITY_ENABLED
|
|
||||||
const AP_Proximity *proximity = AP_Proximity::get_singleton();
|
|
||||||
if (proximity && proximity->get_status() > AP_Proximity::Status::NotConnected) {
|
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
control_sensors_present |=
|
control_sensors_present |=
|
||||||
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
|
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
|
||||||
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
||||||
|
@ -55,6 +47,17 @@ void GCS_Rover::update_vehicle_sensor_status_flags(void)
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; // X/Y position control
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; // X/Y position control
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_PROXIMITY_ENABLED
|
||||||
|
const AP_Proximity *proximity = AP_Proximity::get_singleton();
|
||||||
|
if (proximity && proximity->get_status() > AP_Proximity::Status::NotConnected) {
|
||||||
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||||
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||||
|
}
|
||||||
|
if (proximity && proximity->get_status() != AP_Proximity::Status::NoData) {
|
||||||
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
const RangeFinder *rangefinder = RangeFinder::get_singleton();
|
const RangeFinder *rangefinder = RangeFinder::get_singleton();
|
||||||
if (rangefinder && rangefinder->num_sensors() > 0) {
|
if (rangefinder && rangefinder->num_sensors() > 0) {
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||||
|
@ -64,10 +67,4 @@ void GCS_Rover::update_vehicle_sensor_status_flags(void)
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HAL_PROXIMITY_ENABLED
|
|
||||||
if (proximity && proximity->get_status() != AP_Proximity::Status::NoData) {
|
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue