Browse Source

Copter: set yaw-mode in do_loiter mission command

master
Randy Mackay 12 years ago
parent
commit
b65d714675
  1. 1
      ArduCopter/ArduCopter.pde
  2. 7
      ArduCopter/commands_logic.pde

1
ArduCopter/ArduCopter.pde

@ -1906,6 +1906,7 @@ void update_throttle_mode(void) @@ -1906,6 +1906,7 @@ void update_throttle_mode(void)
get_throttle_althold_with_slew(wp_nav.get_desired_alt(), -wp_nav.get_descent_velocity(), wp_nav.get_climb_velocity());
set_target_alt_for_reporting(wp_nav.get_desired_alt()); // To-Do: return get_destination_alt if we are flying to a waypoint
}
// To-Do: explicitly set what the throttle output should be (probably min throttle). Without setting it the throttle is simply left in it's last position although that is probably zero throttle anyway
break;
case THROTTLE_LAND:

7
ArduCopter/commands_logic.pde

@ -254,7 +254,6 @@ static void do_takeoff() @@ -254,7 +254,6 @@ static void do_takeoff()
}
// do_nav_wp - initiate move to next waypoint
// note: caller should set yaw mode
static void do_nav_wp()
{
// set roll-pitch mode
@ -319,6 +318,9 @@ static void do_loiter_unlimited() @@ -319,6 +318,9 @@ static void do_loiter_unlimited()
// set throttle mode to AUTO which, if not already active, will default to hold at our current altitude
set_throttle_mode(THROTTLE_AUTO);
// hold yaw
set_yaw_mode(YAW_HOLD);
// get current position
// To-Do: change this to projection based on current location and velocity
Vector3f curr = inertial_nav.get_position();
@ -384,6 +386,9 @@ static void do_loiter_time() @@ -384,6 +386,9 @@ static void do_loiter_time()
// set throttle mode to AUTO which, if not already active, will default to hold at our current altitude
set_throttle_mode(THROTTLE_AUTO);
// hold yaw
set_yaw_mode(YAW_HOLD);
// get current position
// To-Do: change this to projection based on current location and velocity
Vector3f curr = inertial_nav.get_position();

Loading…
Cancel
Save