mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: change to use terrain singleton
This commit is contained in:
parent
088120b8f3
commit
05a0205c21
@ -33,6 +33,7 @@
|
|||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_Declination/AP_Declination.h>
|
#include <AP_Declination/AP_Declination.h>
|
||||||
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
|
|
||||||
using namespace SITL;
|
using namespace SITL;
|
||||||
|
|
||||||
@ -63,8 +64,6 @@ Aircraft::Aircraft(const char *frame_str) :
|
|||||||
sitl->ahrs_rotation_inv = sitl->ahrs_rotation.transposed();
|
sitl->ahrs_rotation_inv = sitl->ahrs_rotation.transposed();
|
||||||
}
|
}
|
||||||
|
|
||||||
terrain = AP::terrain();
|
|
||||||
|
|
||||||
// init rangefinder array to -1 to signify no data
|
// init rangefinder array to -1 to signify no data
|
||||||
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++){
|
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++){
|
||||||
rangefinder_m[i] = -1.0f;
|
rangefinder_m[i] = -1.0f;
|
||||||
@ -94,14 +93,18 @@ void Aircraft::set_start_location(const Location &start_loc, const float start_y
|
|||||||
*/
|
*/
|
||||||
float Aircraft::ground_height_difference() const
|
float Aircraft::ground_height_difference() const
|
||||||
{
|
{
|
||||||
|
#if AP_TERRAIN_AVAILABLE
|
||||||
|
AP_Terrain *terrain = AP::terrain();
|
||||||
float h1, h2;
|
float h1, h2;
|
||||||
if (sitl &&
|
if (sitl &&
|
||||||
sitl->terrain_enable && terrain &&
|
terrain != nullptr &&
|
||||||
|
sitl->terrain_enable &&
|
||||||
terrain->height_amsl(home, h1, false) &&
|
terrain->height_amsl(home, h1, false) &&
|
||||||
terrain->height_amsl(location, h2, false)) {
|
terrain->height_amsl(location, h2, false)) {
|
||||||
h2 += local_ground_level;
|
h2 += local_ground_level;
|
||||||
return h2 - h1;
|
return h2 - h1;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
return local_ground_level;
|
return local_ground_level;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -22,7 +22,6 @@
|
|||||||
|
|
||||||
#include "SITL.h"
|
#include "SITL.h"
|
||||||
#include "SITL_Input.h"
|
#include "SITL_Input.h"
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
|
||||||
#include "SIM_Sprayer.h"
|
#include "SIM_Sprayer.h"
|
||||||
#include "SIM_Gripper_Servo.h"
|
#include "SIM_Gripper_Servo.h"
|
||||||
#include "SIM_Gripper_EPM.h"
|
#include "SIM_Gripper_EPM.h"
|
||||||
@ -243,7 +242,6 @@ protected:
|
|||||||
|
|
||||||
bool use_smoothing;
|
bool use_smoothing;
|
||||||
|
|
||||||
AP_Terrain *terrain;
|
|
||||||
float ground_height_difference() const;
|
float ground_height_difference() const;
|
||||||
|
|
||||||
virtual bool on_ground() const;
|
virtual bool on_ground() const;
|
||||||
|
@ -174,21 +174,15 @@ void ShipSim::send_report(void)
|
|||||||
Location loc = home;
|
Location loc = home;
|
||||||
loc.offset_double(ship.position.x, ship.position.y);
|
loc.offset_double(ship.position.x, ship.position.y);
|
||||||
|
|
||||||
int32_t alt;
|
int32_t alt = home.alt; // assume home altitude
|
||||||
bool have_alt = false;
|
|
||||||
|
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE
|
||||||
auto terrain = AP::terrain();
|
auto terrain = AP::terrain();
|
||||||
float height;
|
float height;
|
||||||
if (terrain != nullptr && terrain->enabled() && terrain->height_amsl(loc, height, true)) {
|
if (terrain != nullptr && terrain->enabled() && terrain->height_amsl(loc, height, true)) {
|
||||||
alt = height * 1000;
|
alt = height * 1000;
|
||||||
have_alt = true;
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
if (!have_alt) {
|
|
||||||
// assume home altitude
|
|
||||||
alt = home.alt;
|
|
||||||
}
|
|
||||||
|
|
||||||
Vector2f vel(ship.speed, 0);
|
Vector2f vel(ship.speed, 0);
|
||||||
vel.rotate(radians(ship.heading_deg));
|
vel.rotate(radians(ship.heading_deg));
|
||||||
|
Loading…
Reference in New Issue
Block a user