APM:Copter
sensors.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // return barometric altitude in centimeters
5 {
7 
8  baro_alt = barometer.get_altitude() * 100.0f;
10 
11  motors->set_air_density_ratio(barometer.get_air_density_ratio());
12 }
13 
15 {
16 #if RANGEFINDER_ENABLED == ENABLED
17  rangefinder.init();
18  rangefinder_state.alt_cm_filt.set_cutoff_frequency(RANGEFINDER_WPNAV_FILT_HZ);
20 #endif
21 }
22 
23 // return rangefinder altitude in centimeters
25 {
26 #if RANGEFINDER_ENABLED == ENABLED
28 
29  if (rangefinder.num_sensors() > 0 &&
32  }
33 
35 
37 
38  #if RANGEFINDER_TILT_CORRECTION == ENABLED
39  // correct alt for angle of the rangefinder
40  temp_alt = (float)temp_alt * MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z);
41  #endif
42 
43  rangefinder_state.alt_cm = temp_alt;
44 
45  // filter rangefinder for use by AC_WPNav
46  uint32_t now = AP_HAL::millis();
47 
48  if (rangefinder_state.alt_healthy) {
49  if (now - rangefinder_state.last_healthy_ms > RANGEFINDER_TIMEOUT_MS) {
50  // reset filter if we haven't used it within the last second
51  rangefinder_state.alt_cm_filt.reset(rangefinder_state.alt_cm);
52  } else {
53  rangefinder_state.alt_cm_filt.apply(rangefinder_state.alt_cm, 0.05f);
54  }
55  rangefinder_state.last_healthy_ms = now;
56  }
57 
58  // send rangefinder altitude and health to waypoint navigation library
59  wp_nav->set_rangefinder_alt(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
60 
61 #else
62  rangefinder_state.enabled = false;
63  rangefinder_state.alt_healthy = false;
64  rangefinder_state.alt_cm = 0;
65 #endif
66 }
67 
68 // return true if rangefinder_alt can be used
70 {
71  return (rangefinder_state.enabled && rangefinder_state.alt_healthy);
72 }
73 
74 /*
75  update RPM sensors
76  */
78 {
79 #if RPM_ENABLED == ENABLED
81  if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) {
84  }
85  }
86 #endif
87 }
88 
89 // initialise compass
91 {
92  if (!g.compass_enabled) {
93  return;
94  }
95 
96  if (!compass.init() || !compass.read()) {
97  // make sure we don't pass a broken compass to DCM
98  hal.console->printf("COMPASS INIT ERROR\n");
100  return;
101  }
103 }
104 
105 /*
106  if the compass is enabled then try to accumulate a reading
107  also update initial location used for declination
108  */
110 {
111  if (!g.compass_enabled) {
112  return;
113  }
114 
116 
117  // update initial location used for declination
118  if (!ap.compass_init_location) {
119  Location loc;
120  if (ahrs.get_position(loc)) {
122  ap.compass_init_location = true;
123  }
124  }
125 }
126 
127 // initialise optical flow sensor
129 {
130 #if OPTFLOW == ENABLED
131  // initialise optical flow sensor
132  optflow.init();
133 #endif // OPTFLOW == ENABLED
134 }
135 
136 // called at 200hz
137 #if OPTFLOW == ENABLED
139 {
140  static uint32_t last_of_update = 0;
141 
142  // exit immediately if not enabled
143  if (!optflow.enabled()) {
144  return;
145  }
146 
147  // read from sensor
148  optflow.update();
149 
150  // write to log and send to EKF if new data has arrived
151  if (optflow.last_update() != last_of_update) {
152  last_of_update = optflow.last_update();
153  uint8_t flowQuality = optflow.quality();
154  Vector2f flowRate = optflow.flowRate();
155  Vector2f bodyRate = optflow.bodyRate();
156  const Vector3f &posOffset = optflow.get_pos_offset();
157  ahrs.writeOptFlowMeas(flowQuality, flowRate, bodyRate, last_of_update, posOffset);
160  }
161  }
162 }
163 #endif // OPTFLOW == ENABLED
164 
166 {
167  static uint32_t compass_cal_stick_gesture_begin = 0;
168 
169  if (!hal.util->get_soft_armed()) {
171  }
172 
173  if (compass.is_calibrating()) {
174  if (channel_yaw->get_control_in() < -4000 && channel_throttle->get_control_in() > 900) {
176  }
177  } else {
178  bool stick_gesture_detected = compass_cal_stick_gesture_begin != 0 && !motors->armed() && channel_yaw->get_control_in() > 4000 && channel_throttle->get_control_in() > 900;
179  uint32_t tnow = millis();
180 
181  if (!stick_gesture_detected) {
182  compass_cal_stick_gesture_begin = tnow;
183  } else if (tnow-compass_cal_stick_gesture_begin > 1000*COMPASS_CAL_STICK_GESTURE_TIME) {
184 #ifdef CAL_ALWAYS_REBOOT
186 #else
188 #endif
189  }
190  }
191 }
192 
194 {
195  if (hal.util->get_soft_armed()) {
196  return;
197  }
198  ins.acal_update();
199  // check if new trim values, and set them
200  float trim_roll, trim_pitch;
201  if(ins.get_new_trim(trim_roll, trim_pitch)) {
202  ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
203  }
204 
205 #ifdef CAL_ALWAYS_REBOOT
207  hal.scheduler->delay(1000);
208  hal.scheduler->reboot(false);
209  }
210 #endif
211 }
212 
213 // initialise proximity sensor
215 {
216 #if PROXIMITY_ENABLED == ENABLED
217  g2.proximity.init();
219 #endif
220 }
221 
222 // update error mask of sensors and subsystems. The mask
223 // uses the MAV_SYS_STATUS_* values from mavlink. If a bit is set
224 // then it indicates that the sensor or subsystem is present but
225 // not functioning correctly.
227 {
228  // default sensors present
230 
231  // first what sensors/controllers we have
232  if (g.compass_enabled) {
233  control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG; // compass present
234  }
235  if (gps.status() > AP_GPS::NO_GPS) {
236  control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
237  }
238 #if OPTFLOW == ENABLED
239  if (optflow.enabled()) {
240  control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
241  }
242 #endif
243 #if PRECISION_LANDING == ENABLED
244  if (precland.enabled()) {
245  control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
246  }
247 #endif
248 #if VISUAL_ODOMETRY_ENABLED == ENABLED
249  if (g2.visual_odom.enabled()) {
250  control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
251  }
252 #endif
253  if (ap.rc_receiver_present) {
254  control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
255  }
256  if (copter.DataFlash.logging_present()) { // primary logging only (usually File)
257  control_sensors_present |= MAV_SYS_STATUS_LOGGING;
258  }
259 #if PROXIMITY_ENABLED == ENABLED
260  if (copter.g2.proximity.get_status() > AP_Proximity::Proximity_NotConnected) {
261  control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
262  }
263 #endif
264 #if AC_FENCE == ENABLED
265  if (copter.fence.sys_status_present()) {
266  control_sensors_present |= MAV_SYS_STATUS_GEOFENCE;
267  }
268 #endif
269 
270  // all present sensors enabled by default except altitude and position control and motors which we will set individually
271  control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL &
272  ~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL &
273  ~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS &
274  ~MAV_SYS_STATUS_LOGGING &
275  ~MAV_SYS_STATUS_SENSOR_BATTERY &
276  ~MAV_SYS_STATUS_GEOFENCE);
277 
278  switch (control_mode) {
279  case AUTO:
280  case AVOID_ADSB:
281  case GUIDED:
282  case LOITER:
283  case RTL:
284  case CIRCLE:
285  case LAND:
286  case POSHOLD:
287  case BRAKE:
288  case THROW:
289  case SMART_RTL:
290  control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
291  control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
292  break;
293  case ALT_HOLD:
294  case GUIDED_NOGPS:
295  case SPORT:
296  case AUTOTUNE:
297  case FLOWHOLD:
298  control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
299  break;
300  default:
301  // stabilize, acro, drift, and flip have no automatic x,y or z control (i.e. all manual)
302  break;
303  }
304 
305  // set motors outputs as enabled if safety switch is not disarmed (i.e. either NONE or ARMED)
307  control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS;
308  }
309 
310  if (copter.DataFlash.logging_enabled()) {
311  control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
312  }
313 
314  if (battery.num_instances() > 0) {
315  control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_BATTERY;
316  }
317 #if AC_FENCE == ENABLED
318  if (copter.fence.sys_status_enabled()) {
319  control_sensors_enabled |= MAV_SYS_STATUS_GEOFENCE;
320  }
321 #endif
322 
323 
324  // default to all healthy
326 
327  if (!barometer.all_healthy()) {
328  control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
329  }
330  if (!g.compass_enabled || !compass.healthy() || !ahrs.use_compass()) {
331  control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_MAG;
332  }
333  if (!gps.is_healthy()) {
334  control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_GPS;
335  }
336  if (!ap.rc_receiver_present || failsafe.radio) {
337  control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
338  }
339 #if OPTFLOW == ENABLED
340  if (!optflow.healthy()) {
341  control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
342  }
343 #endif
344 #if PRECISION_LANDING == ENABLED
345  if (precland.enabled() && !precland.healthy()) {
346  control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_VISION_POSITION;
347  }
348 #endif
349 #if VISUAL_ODOMETRY_ENABLED == ENABLED
350  if (g2.visual_odom.enabled() && !g2.visual_odom.healthy()) {
351  control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_VISION_POSITION;
352  }
353 #endif
355  control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_GYRO;
356  }
357  if (!ins.get_accel_health_all()) {
358  control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_ACCEL;
359  }
360 
361  if (ahrs.initialised() && !ahrs.healthy()) {
362  // AHRS subsystem is unhealthy
363  control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
364  }
365 
366  if (copter.DataFlash.logging_failed()) {
367  control_sensors_health &= ~MAV_SYS_STATUS_LOGGING;
368  }
369 
370 #if PROXIMITY_ENABLED == ENABLED
371  if (copter.g2.proximity.get_status() == AP_Proximity::Proximity_NoData) {
372  control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_LASER_POSITION;
373  }
374 #endif
375 
376 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
377  switch (terrain.status()) {
378  case AP_Terrain::TerrainStatusDisabled:
379  break;
380  case AP_Terrain::TerrainStatusUnhealthy:
381  // To-Do: restore unhealthy terrain status reporting once terrain is used in copter
382  //control_sensors_present |= MAV_SYS_STATUS_TERRAIN;
383  //control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN;
384  //break;
385  case AP_Terrain::TerrainStatusOK:
386  control_sensors_present |= MAV_SYS_STATUS_TERRAIN;
387  control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN;
388  control_sensors_health |= MAV_SYS_STATUS_TERRAIN;
389  break;
390  }
391 #endif
392 
393 #if RANGEFINDER_ENABLED == ENABLED
394  if (rangefinder_state.enabled) {
395  control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
396  control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
398  control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
399  }
400  }
401 #endif
402 
403  if (!ap.initialised || ins.calibrating()) {
404  // while initialising the gyros and accels are not enabled
405  control_sensors_enabled &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
406  control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
407  }
408 
409  if (!copter.battery.healthy() || copter.battery.has_failsafed()) {
410  control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_BATTERY;
411  }
412 #if AC_FENCE == ENABLED
413  if (copter.fence.sys_status_failed()) {
414  control_sensors_health &= ~MAV_SYS_STATUS_GEOFENCE;
415  }
416 #endif
417 
418 #if FRSKY_TELEM_ENABLED == ENABLED
419  // give mask of error flags to Frsky_Telemetry
421 #endif
422 }
423 
424 // init visual odometry sensor
426 {
427 #if VISUAL_ODOMETRY_ENABLED == ENABLED
428  g2.visual_odom.init();
429 #endif
430 }
431 
432 // update visual odometry sensor
434 {
435 #if VISUAL_ODOMETRY_ENABLED == ENABLED
436  // check for updates
439  float time_delta_sec = g2.visual_odom.get_time_delta_usec() / 1000000.0f;
443  time_delta_sec,
446  // log sensor data
447  DataFlash.Log_Write_VisualOdom(time_delta_sec,
451  }
452 #endif
453 }
454 
455 // winch and wheel encoder initialisation
457 {
458 #if WINCH_ENABLED == ENABLED
461 #endif
462 }
463 
464 // winch and wheel encoder update
466 {
467 #if WINCH_ENABLED == ENABLED
469  g2.winch.update();
470 #endif
471 }
bool accel_cal_requires_reboot() const
bool get_soft_armed() const
float get_climb_rate(void)
bool has_data_orient(enum Rotation orientation) const
void update(void)
void read_barometer(void)
Definition: sensors.cpp:4
#define MASK_LOG_RCIN
Definition: defines.h:320
bool enabled(uint8_t instance) const
bool initialised() const override
bool use_compass() override
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
void set_compass(Compass *compass)
bool rangefinder_alt_ok()
Definition: sensors.cpp:69
int32_t baro_alt
Definition: Copter.h:466
void rpm_update()
Definition: sensors.cpp:77
AP_Baro barometer
Definition: Copter.h:234
#define MASK_LOG_CTUN
Definition: defines.h:318
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
void update(void)
ROTATION_PITCH_270
AP_VisualOdom visual_odom
Definition: Parameters.h:534
void update(void)
#define RANGEFINDER_TIMEOUT_MS
Definition: config.h:100
bool healthy() const override
AP_HAL::UARTDriver * console
bool healthy() const
AP_InertialSensor ins
Definition: Copter.h:236
void init_rangefinder(void)
Definition: sensors.cpp:14
void init_proximity()
Definition: sensors.cpp:214
void start_calibration_all(bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot=false)
#define RANGEFINDER_HEALTH_MAX
Definition: config.h:88
AP_WheelEncoder wheel_encoder
Definition: Parameters.h:575
#define MASK_LOG_OPTFLOW
Definition: defines.h:325
bool has_orientation(enum Rotation orientation) const
AC_WPNav * wp_nav
Definition: Copter.h:494
RangeFinder rangefinder
Definition: Copter.h:238
Definition: defines.h:95
Definition: defines.h:106
bool init()
uint8_t range_valid_count_orient(enum Rotation orientation) const
void Log_Write_Optflow()
Definition: Log.cpp:73
AP_HAL::Util * util
void cancel_calibration_all()
struct Copter::@0 rangefinder_state
Definition: defines.h:96
Definition: defines.h:100
#define ERROR_SUBSYSTEM_COMPASS
Definition: defines.h:395
const Vector3f & get_angle_delta() const
void accumulate()
uint32_t control_sensors_health
Definition: Copter.h:460
AP_Frsky_Telem frsky_telemetry
Definition: Copter.h:451
bool is_healthy(uint8_t instance) const
bool read()
AP_Proximity proximity
Definition: Parameters.h:539
bool should_log(uint32_t mask)
Definition: system.cpp:435
uint8_t num_sensors(void) const
Definition: defines.h:102
RC_Channel * channel_yaw
Definition: Copter.h:224
MOTOR_CLASS * motors
Definition: Copter.h:422
AP_Int32 log_bitmask
Definition: Parameters.h:438
int32_t lat
bool healthy() const
uint64_t get_time_delta_usec() const
const Vector2f & flowRate() const
bool enabled() const
void update_visual_odom()
Definition: sensors.cpp:433
float get_air_density_ratio(void)
virtual void delay(uint16_t ms)=0
void update_sensor_status_flags(uint32_t error_mask)
void update()
void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
Definition: Log.cpp:328
uint8_t terrain
Definition: Copter.h:400
virtual void printf(const char *,...) FMT_PRINTF(2
virtual void set_trim(Vector3f new_trim)
RC_Channel * channel_throttle
Definition: Copter.h:223
const Vector3f & get_position_delta() const
void init(const AP_WheelEncoder *wheel_encoder=nullptr)
void Log_Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence)
void winch_update()
Definition: sensors.cpp:465
bool calibrating() const
int16_t get_control_in() const
uint32_t get_last_update_ms() const
bool get_accel_health_all(void) const
#define COMPASS_CAL_STICK_DELAY
Definition: config.h:202
AP_RPM rpm_sensor
Definition: Copter.h:249
void init_optflow()
Definition: sensors.cpp:128
#define f(i)
AP_BattMonitor battery
Definition: Copter.h:445
#define ERROR_CODE_FAILED_TO_INITIALISE
Definition: defines.h:419
uint8_t quality() const
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
void init_compass()
Definition: sensors.cpp:90
Vector3< float > c
uint32_t millis()
void update_sensor_status_flags(void)
Definition: sensors.cpp:226
AP_Winch winch
Definition: Parameters.h:576
uint16_t distance_cm_orient(enum Rotation orientation) const
virtual enum safety_state safety_switch_state(void)
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
Definition: defines.h:99
float baro_climbrate
Definition: Copter.h:467
uint32_t last_update() const
bool healthy[COMPASS_MAX_INSTANCES]
Definition: defines.h:97
bool get_position(struct Location &loc) const override
Definition: defines.h:107
bool healthy() const
const Vector2f & bodyRate() const
GPS_Status status(uint8_t instance) const
AC_PrecLand precland
Definition: Copter.h:566
void init(void)
DataFlash_Class DataFlash
Definition: Copter.h:227
AP_GPS gps
Definition: Copter.h:229
void Log_Write_RPM(const AP_RPM &rpm_sensor)
uint32_t control_sensors_enabled
Definition: Copter.h:459
Parameters g
Definition: Copter.h:208
float get_altitude(void) const
virtual void reboot(bool hold_in_bootloader)=0
AP_Int8 compass_enabled
Definition: Parameters.h:401
bool enabled() const
int32_t lng
void init(void)
RangeFinder_Status status_orient(enum Rotation orientation) const
Compass compass
Definition: Copter.h:235
void compass_cal_update()
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
const Matrix3f & get_rotation_body_to_ned(void) const override
struct Copter::@2 failsafe
void init(void)
void update_optical_flow(void)
Definition: sensors.cpp:138
void compass_accumulate(void)
Definition: sensors.cpp:109
bool gyro_calibrated_ok_all() const
bool get_new_trim(float &trim_roll, float &trim_pitch)
bool is_calibrating() const
uint32_t control_sensors_present
Definition: Copter.h:458
void init_visual_odom()
Definition: sensors.cpp:425
OpticalFlow optflow
Definition: Copter.h:284
void update(void)
ParametersG2 g2
Definition: Copter.h:209
#define RANGEFINDER_WPNAV_FILT_HZ
Definition: config.h:104
void Log_Write_RFND(const RangeFinder &rangefinder)
void update(void)
uint8_t num_instances(void) const
void init(void)
void accel_cal_update(void)
Definition: sensors.cpp:193
control_mode_t control_mode
Definition: Copter.h:345
void compass_cal_update(void)
Definition: sensors.cpp:165
bool enabled() const
uint32_t visual_odom_last_update_ms
Definition: Copter.h:590
void set_rangefinder_alt(bool use, bool healthy, float alt_cm)
float get_confidence() const
bool get_gyro_health_all(void) const
void set_initial_location(int32_t latitude, int32_t longitude)
bool all_healthy(void) const
void winch_init()
Definition: sensors.cpp:456
const Vector3f & get_pos_offset(void) const
AP_HAL::Scheduler * scheduler
#define COMPASS_CAL_STICK_GESTURE_TIME
Definition: config.h:199
void read_rangefinder(void)
Definition: sensors.cpp:24
Definition: defines.h:98
const Vector3f & get_pos_offset(void) const
void set_rangefinder(const RangeFinder *rangefinder)