mirror of https://github.com/ArduPilot/ardupilot
Added support for WP options
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1743 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
8fbe11fca5
commit
cac0a18760
|
@ -959,6 +959,7 @@ void update_navigation()
|
||||||
// distance and bearing calcs only
|
// distance and bearing calcs only
|
||||||
if(control_mode == AUTO || control_mode == GCS_AUTO){
|
if(control_mode == AUTO || control_mode == GCS_AUTO){
|
||||||
verify_commands();
|
verify_commands();
|
||||||
|
|
||||||
}else{
|
}else{
|
||||||
switch(control_mode){
|
switch(control_mode){
|
||||||
case RTL:
|
case RTL:
|
||||||
|
|
|
@ -255,5 +255,8 @@ void output_manual_yaw()
|
||||||
|
|
||||||
void auto_yaw()
|
void auto_yaw()
|
||||||
{
|
{
|
||||||
|
if(next_WP.options & WP_OPT_YAW){
|
||||||
|
nav_yaw = target_bearing;
|
||||||
|
}
|
||||||
output_yaw_with_hold(true); // hold yaw
|
output_yaw_with_hold(true); // hold yaw
|
||||||
}
|
}
|
||||||
|
|
|
@ -101,8 +101,9 @@ void calc_bearing_error()
|
||||||
void calc_altitude_error()
|
void calc_altitude_error()
|
||||||
{
|
{
|
||||||
//if(control_mode == AUTO && offset_altitude != 0) {
|
//if(control_mode == AUTO && offset_altitude != 0) {
|
||||||
if(next_WP.options & WP_OPT_ALT_CHANGE) {
|
if(next_WP.options & WP_OPT_ALT_CHANGE || offset_altitude == 0) {
|
||||||
target_altitude = next_WP.alt;
|
target_altitude = next_WP.alt;
|
||||||
|
|
||||||
}else{
|
}else{
|
||||||
// limit climb rates - we draw a straight line between first location and edge of waypoint_radius
|
// limit climb rates - we draw a straight line between first location and edge of waypoint_radius
|
||||||
target_altitude = next_WP.alt - ((wp_distance * offset_altitude) / (wp_totalDistance - g.waypoint_radius));
|
target_altitude = next_WP.alt - ((wp_distance * offset_altitude) / (wp_totalDistance - g.waypoint_radius));
|
||||||
|
|
Loading…
Reference in New Issue