mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: sensors.cpp correct whitespace, remove tabs
This commit is contained in:
parent
25fbfeb5cf
commit
51aaa7efa7
@ -30,7 +30,7 @@ void Rover::read_receiver_rssi(void)
|
||||
receiver_rssi = rssi.read_receiver_rssi_uint8();
|
||||
}
|
||||
|
||||
//Calibrate compass
|
||||
// Calibrate compass
|
||||
void Rover::compass_cal_update() {
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
compass.compass_cal_update();
|
||||
@ -45,8 +45,8 @@ void Rover::accel_cal_update() {
|
||||
}
|
||||
ins.acal_update();
|
||||
// check if new trim values, and set them float trim_roll, trim_pitch;
|
||||
float trim_roll,trim_pitch;
|
||||
if(ins.get_new_trim(trim_roll, trim_pitch)) {
|
||||
float trim_roll, trim_pitch;
|
||||
if (ins.get_new_trim(trim_roll, trim_pitch)) {
|
||||
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
||||
}
|
||||
}
|
||||
@ -149,7 +149,12 @@ void Rover::update_sensor_status_flags(void)
|
||||
|
||||
|
||||
// all present sensors enabled by default except rate control, attitude stabilization, yaw, altitude, position control and motor output which we will set individually
|
||||
control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL & ~MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION & ~MAV_SYS_STATUS_SENSOR_YAW_POSITION & ~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL & ~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS & ~MAV_SYS_STATUS_LOGGING);
|
||||
control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL &
|
||||
~MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION &
|
||||
~MAV_SYS_STATUS_SENSOR_YAW_POSITION &
|
||||
~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL &
|
||||
~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS &
|
||||
~MAV_SYS_STATUS_LOGGING);
|
||||
|
||||
switch (control_mode) {
|
||||
case MANUAL:
|
||||
@ -223,7 +228,6 @@ void Rover::update_sensor_status_flags(void)
|
||||
control_sensors_enabled &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
|
||||
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
|
||||
}
|
||||
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// give mask of error flags to Frsky_Telemetry
|
||||
frsky_telemetry.update_sensor_status_flags(~control_sensors_health & control_sensors_enabled & control_sensors_present);
|
||||
|
Loading…
Reference in New Issue
Block a user