mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-13 11:28:30 -04:00
altitude was set to sonar pid rather than baro pid
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1528 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
b830afd678
commit
b912b7e0eb
@ -259,7 +259,7 @@ float roll; // radians
|
||||
float pitch; // radians
|
||||
float yaw; // radians
|
||||
|
||||
byte altitude_sensor = SONAR; // used to know whic sensor is active, BARO or SONAR
|
||||
byte altitude_sensor = BARO; // used to know whic sensor is active, BARO or SONAR
|
||||
|
||||
// flight mode specific
|
||||
// --------------------
|
||||
@ -851,7 +851,7 @@ void update_current_flight_mode(void)
|
||||
nav_roll = 0;
|
||||
|
||||
// get desired height from the throttle
|
||||
next_WP.alt = home.alt + (rc_3.control_in * 4) -100; // 0 - 1000 (40 meters)
|
||||
next_WP.alt = home.alt + (rc_3.control_in * 4); // 0 - 1000 (40 meters)
|
||||
|
||||
// Yaw control
|
||||
// -----------
|
||||
|
Loading…
Reference in New Issue
Block a user