mirror of https://github.com/ArduPilot/ardupilot
Copter: add TERRAIN_USE parameter
Also add terrain.cpp to hold terrain_update and terrain_logging functions
This commit is contained in:
parent
267c1c3934
commit
91f6c7b503
|
@ -132,6 +132,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
SCHED_TASK(frsky_telemetry_send, 5, 75),
|
||||
#endif
|
||||
SCHED_TASK(terrain_update, 10, 100),
|
||||
#if EPM_ENABLED == ENABLED
|
||||
SCHED_TASK(epm_update, 10, 75),
|
||||
#endif
|
||||
|
@ -498,24 +499,14 @@ void Copter::one_hz_loop()
|
|||
|
||||
check_usb_mux();
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
terrain.update();
|
||||
|
||||
// tell the rangefinder our height, so it can go into power saving
|
||||
// mode if available
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
float height;
|
||||
if (terrain.height_above_terrain(height, true)) {
|
||||
sonar.set_estimated_terrain_height(height);
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// update position controller alt limits
|
||||
update_poscon_alt_max();
|
||||
|
||||
// enable/disable raw gyro/accel logging
|
||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||
|
||||
// log terrain data
|
||||
terrain_logging();
|
||||
}
|
||||
|
||||
// called at 50hz
|
||||
|
|
|
@ -945,6 +945,9 @@ private:
|
|||
void read_battery(void);
|
||||
void read_receiver_rssi(void);
|
||||
void epm_update();
|
||||
void terrain_update();
|
||||
void terrain_logging();
|
||||
bool terrain_use();
|
||||
void report_batt_monitor();
|
||||
void report_frame();
|
||||
void report_radio();
|
||||
|
|
|
@ -960,6 +960,13 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @User: Standard
|
||||
GSCALAR(throw_motor_start, "THROW_MOT_START", 0),
|
||||
|
||||
// @Param: TERRAIN_USE
|
||||
// @DisplayName: Terrain use control
|
||||
// @Description: Control how terrain data is used
|
||||
// @Values: 0:NeverUse, 1:AlwaysUse
|
||||
// @User: Standard
|
||||
GSCALAR(terrain_use, "TERRAIN_USE", 0),
|
||||
|
||||
AP_VAREND
|
||||
};
|
||||
|
||||
|
|
|
@ -179,6 +179,7 @@ public:
|
|||
k_param_disarm_delay,
|
||||
k_param_fs_crash_check,
|
||||
k_param_throw_motor_start,
|
||||
k_param_terrain_use, // 94
|
||||
|
||||
// 97: RSSI
|
||||
k_param_rssi = 97,
|
||||
|
@ -452,6 +453,7 @@ public:
|
|||
AP_Int16 gcs_pid_mask;
|
||||
|
||||
AP_Int8 throw_motor_start;
|
||||
AP_Int8 terrain_use;
|
||||
|
||||
// RC channels
|
||||
RC_Channel rc_1;
|
||||
|
|
|
@ -0,0 +1,40 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include "Copter.h"
|
||||
|
||||
// update terrain data
|
||||
void Copter::terrain_update()
|
||||
{
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
terrain.update();
|
||||
|
||||
// tell the rangefinder our height, so it can go into power saving
|
||||
// mode if available
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
float height;
|
||||
if (terrain.height_above_terrain(height, true)) {
|
||||
sonar.set_estimated_terrain_height(height);
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
// log terrain data - should be called at 1hz
|
||||
void Copter::terrain_logging()
|
||||
{
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
if (should_log(MASK_LOG_GPS)) {
|
||||
terrain.log_terrain_data(DataFlash);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// should we use terrain data for things including the home altitude
|
||||
bool Copter::terrain_use()
|
||||
{
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
return (g.terrain_use > 0);
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
Loading…
Reference in New Issue