Closed eeroniemi closed 2 years ago
Have you tried flying the simulator at a different location with significant attitude different, like 100m?
Have you tried flying the simulator at a different location with significant attitude different, like 100m?
I have only tried place which has small hill and altitude difference between top of that and ground level close to it is about 10 meters, and this causes copter to crash when it hits altitude 0. I cannot think of reasons why the same thing would not happen if altitude difference would be more?
In case anyone bumps into this, a fairly quick and ugly hack that allows the simulator to go to the negative altitude range is this:
diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp
index 555ab1add..8da01b8f6 100644
--- a/libraries/SITL/SIM_Aircraft.cpp
+++ b/libraries/SITL/SIM_Aircraft.cpp
@@ -172,7 +172,11 @@ float Aircraft::hagl() const
*/
bool Aircraft::on_ground() const
{
- return hagl() <= 0.001f; // prevent bouncing around ground
+ if (abs(position.x) < 3 && abs(position.y) < 3) {
+ return hagl() <= 0.001f; // prevent bouncing around ground
+ } else {
+ return 0;
+ }
}
/*
This basically creates a 6x6m square around the home position where the terrain behaves "normal"; everywhere else it's a chasm with infinite depth. Works for the use-case where you will be landing the aircraft at the home position at the end of the flight.
We now have autotests which check the vehicle can fly below the takeoff point, so I think I'll close this now as "fixed, by someone, sometime" :-)
Feature request
Is your feature request related to a problem? Please describe.
We are trying to simulate a mission where the copter home/takoff location is on top of the hill, and one of the waypoints happens to be lower than our takeoff point. What happens is that when the copter reaches the point where altitude goes below the takeoff point (altitude 0) the copter stops moving, and after a while we get crash messages to the console:
I have tried to solve this problem by enabling virtual rangefinder on SITL (by using this guide) - it reports the rangefinder distance (RANGEFINDER.distance) to the ground correctly like it would in real life, but copter still crashes at 0 altitude, even if rangefinder says we are still 10 meters from the ground. I also tried to set
EK2_RNG_USE_HGT
to 1 and 70% but it didn't help.Describe the solution you'd like Looks like SITL knows the real terrain altitude (based on the simulated rangefinder data), but the terrain is still flat. Having uneven terrain on simulator would be great feature to have to simulate more complex missions (takeoff from the roofpoint and delivery to ground level etc.).
Platform [ ] All [ ] AntennaTracker [ x ] Copter [ ] Plane [ ] Rover [ ] Submarine