mirror of https://github.com/ArduPilot/ardupilot
GCS Alt fix.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2287 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
873d7bb5d5
commit
c95419fbf5
|
@ -400,12 +400,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
// command needs scaling
|
// command needs scaling
|
||||||
x = tell_command.lat/1.0e7; // local (x), global (latitude)
|
x = tell_command.lat/1.0e7; // local (x), global (latitude)
|
||||||
y = tell_command.lng/1.0e7; // local (y), global (longitude)
|
y = tell_command.lng/1.0e7; // local (y), global (longitude)
|
||||||
if (tell_command.options & WP_OPTION_ALT_RELATIVE) {
|
// ACM is processing alt inside each command. so we save and load raw values. - this is diffrent to APM
|
||||||
z = (tell_command.alt - home.alt) / 1.0e2; // because tell_command.alt already includes a += home.alt
|
|
||||||
} else {
|
|
||||||
z = tell_command.alt/1.0e2; // local (z), global/relative (altitude)
|
z = tell_command.alt/1.0e2; // local (z), global/relative (altitude)
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
switch (tell_command.id) { // Switch to map APM command fields inot MAVLink command fields
|
switch (tell_command.id) { // Switch to map APM command fields inot MAVLink command fields
|
||||||
|
|
Loading…
Reference in New Issue