mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: convert to unix style end-of-line
This commit is contained in:
parent
f9c35772fe
commit
5ce185e4ac
|
@ -1,29 +1,29 @@
|
|||
//
|
||||
// functions to support precision landing
|
||||
//
|
||||
|
||||
#include "Copter.h"
|
||||
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
|
||||
void Copter::init_precland()
|
||||
{
|
||||
copter.precland.init(400);
|
||||
}
|
||||
|
||||
void Copter::update_precland()
|
||||
{
|
||||
int32_t height_above_ground_cm = current_loc.alt;
|
||||
|
||||
// use range finder altitude if it is valid, else try to get terrain alt
|
||||
if (rangefinder_alt_ok()) {
|
||||
height_above_ground_cm = rangefinder_state.alt_cm;
|
||||
} else if (terrain_use()) {
|
||||
if (!current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, height_above_ground_cm)) {
|
||||
height_above_ground_cm = current_loc.alt;
|
||||
}
|
||||
}
|
||||
|
||||
precland.update(height_above_ground_cm, rangefinder_alt_ok());
|
||||
}
|
||||
#endif
|
||||
//
|
||||
// functions to support precision landing
|
||||
//
|
||||
|
||||
#include "Copter.h"
|
||||
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
|
||||
void Copter::init_precland()
|
||||
{
|
||||
copter.precland.init(400);
|
||||
}
|
||||
|
||||
void Copter::update_precland()
|
||||
{
|
||||
int32_t height_above_ground_cm = current_loc.alt;
|
||||
|
||||
// use range finder altitude if it is valid, else try to get terrain alt
|
||||
if (rangefinder_alt_ok()) {
|
||||
height_above_ground_cm = rangefinder_state.alt_cm;
|
||||
} else if (terrain_use()) {
|
||||
if (!current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, height_above_ground_cm)) {
|
||||
height_above_ground_cm = current_loc.alt;
|
||||
}
|
||||
}
|
||||
|
||||
precland.update(height_above_ground_cm, rangefinder_alt_ok());
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -1,38 +1,38 @@
|
|||
#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 RANGEFINDER_ENABLED == ENABLED
|
||||
float height;
|
||||
if (terrain.height_above_terrain(height, true)) {
|
||||
rangefinder.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();
|
||||
}
|
||||
#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_follow > 0);
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
#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 RANGEFINDER_ENABLED == ENABLED
|
||||
float height;
|
||||
if (terrain.height_above_terrain(height, true)) {
|
||||
rangefinder.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();
|
||||
}
|
||||
#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_follow > 0);
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue