SITL: removed vehicle specific ground handling

This commit is contained in:
Andrew Tridgell 2016-07-19 14:47:47 +10:00
parent e7a54c83d1
commit 4faa57074a
3 changed files with 0 additions and 31 deletions

View File

@ -162,17 +162,6 @@ void Helicopter::update(const struct sitl_input &input)
update_dynamics(rot_accel);
// constrain height to the ground
if (on_ground(position) && !was_on_ground) {
// zero roll/pitch, but keep yaw
float r, p, y;
dcm.to_euler(&r, &p, &y);
dcm.from_euler(0, 0, y);
position.z = -(ground_level + frame_height - home.alt*0.01f + ground_height_difference);
velocity_ef.zero();
}
// update lat/lon/altitude
update_position();

View File

@ -62,15 +62,6 @@ void MultiCopter::update(const struct sitl_input &input)
update_dynamics(rot_accel);
if (on_ground(position)) {
// zero roll/pitch, but keep yaw
float r, p, y;
dcm.to_euler(&r, &p, &y);
dcm.from_euler(0, 0, y);
position.z = -(ground_level + frame_height - home.alt*0.01f + ground_height_difference);
}
// update lat/lon/altitude
update_position();

View File

@ -102,17 +102,6 @@ void SingleCopter::update(const struct sitl_input &input)
update_dynamics(rot_accel);
// constrain height to the ground
if (on_ground(position) && !was_on_ground) {
// zero roll/pitch, but keep yaw
float r, p, y;
dcm.to_euler(&r, &p, &y);
dcm.from_euler(0, 0, y);
position.z = -(ground_level + frame_height - home.alt*0.01f + ground_height_difference);
velocity_ef.zero();
}
// update lat/lon/altitude
update_position();