Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix ArduPilot starting alt locations #23674

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@

# get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__))
SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 584, 270)
SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 586.3, 270)

# Flight mode switch positions are set-up in arducopter.param to be
# switch 1 = Circle
Expand Down
4 changes: 2 additions & 2 deletions Tools/autotest/locations.txt
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
#NAME=latitude,longitude,absolute-altitude,heading
OSRF0=37.4003371,-122.0800351,0,353
OSRF0_PILOTSBOX=37.4003371,-122.0800351,2,270
CMAC=-35.363261,149.165230,584,353
CMAC2=-35.362889,149.165221,584,270
CMAC=-35.363261,149.165230,586.3,353
CMAC2=-35.362889,149.165221,586.3,270
CMAC_South=-35.363261,149.165230,584,173
CMAC_PILOTSBOX=-35.362734,149.165300,586,270
CMAC_PILOTSBOX2=-35.362749,149.165359,584,270
Expand Down
9 changes: 9 additions & 0 deletions libraries/AP_HAL_SITL/SITL_State.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <AP_Param/AP_Param.h>
#include <SITL/SIM_JSBSim.h>
#include <AP_HAL/utility/Socket.h>
#include <GCS_MAVLink/GCS.h>

extern const AP_HAL::HAL& hal;

Expand Down Expand Up @@ -596,6 +597,14 @@ void SITL_State::set_height_agl(void)
if (_terrain != nullptr &&
_terrain->height_amsl(location, terrain_height_amsl, false)) {
_sitl->height_agl = _sitl->state.altitude - terrain_height_amsl;
if (_sitl->height_agl < 0) {
static bool sent_warning_clamp;
if (!sent_warning_clamp) {
sent_warning_clamp = true;
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Clamping simulated height agl to zero from (%f)", _sitl->height_agl);
}
_sitl->height_agl = 0;
}
return;
}
}
Expand Down
3 changes: 3 additions & 0 deletions libraries/SITL/SIM_Aircraft.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -555,6 +555,9 @@ float Aircraft::rangefinder_range() const
// Add some noise on reading
altitude += sitl->sonar_noise * rand_float();

// this rangefinder is mounted on the simulated frame, 5cm off the ground:
altitude += 0.05;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this jive with RNGFND1_GNDCLEAR?


return altitude;
}

Expand Down
2 changes: 1 addition & 1 deletion libraries/SITL/SITL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -285,7 +285,7 @@ const AP_Param::GroupInfo SIM::var_info2[] = {
// @DisplayName: Original Position (Altitude)
// @Description: Specifies vehicle's startup altitude (AMSL)
// @User: Advanced
AP_GROUPINFO("OPOS_ALT", 53, SIM, opos.alt, 584.0f),
AP_GROUPINFO("OPOS_ALT", 53, SIM, opos.alt, 586.3f),
// @Param: OPOS_HDG
// @DisplayName: Original Position (Heading)
// @Description: Specifies vehicle's startup heading (0-360)
Expand Down
Loading