Randy Mackay
7 years ago
5 changed files with 29 additions and 41 deletions
@ -1,41 +1,33 @@
@@ -1,41 +1,33 @@
|
||||
#include "mode.h" |
||||
#include "Rover.h" |
||||
|
||||
void ModeSimple::init_simple_heading() |
||||
void ModeSimple::init_heading() |
||||
{ |
||||
simple_initial_heading = ahrs.yaw; |
||||
_initial_heading_cd = ahrs.yaw_sensor; |
||||
_desired_heading_cd = ahrs.yaw_sensor; |
||||
} |
||||
|
||||
void ModeSimple::update() |
||||
{ |
||||
float desired_heading, desired_steering, desired_speed; |
||||
float desired_heading_cd, desired_speed; |
||||
|
||||
// initial heading simple mode
|
||||
if (g2.simple_type == Simple_InitialHeading) { |
||||
|
||||
// get piot input
|
||||
get_pilot_desired_steering_and_speed(desired_steering, desired_speed); |
||||
// get pilot input
|
||||
get_pilot_desired_heading_and_speed(desired_heading_cd, desired_speed); |
||||
|
||||
float simple_heading; |
||||
if (is_zero(desired_steering)) { |
||||
simple_heading = ((simple_initial_heading - ahrs.yaw) * 4500.0f); |
||||
} else { |
||||
simple_heading = desired_steering; |
||||
} |
||||
|
||||
// run throttle and steering controllers
|
||||
calc_steering_to_heading(simple_heading, false); |
||||
calc_throttle(desired_speed, true, false); |
||||
// rotate heading around based on initial heading
|
||||
if (g2.simple_type == Simple_InitialHeading) { |
||||
desired_heading_cd = wrap_360_cd(_initial_heading_cd + desired_heading_cd); |
||||
} |
||||
|
||||
// cardinal directions simple mode
|
||||
if (g2.simple_type == Simple_CardinalDirections) { |
||||
|
||||
// get pilot input
|
||||
get_pilot_desired_heading_and_speed(desired_heading, desired_speed); |
||||
|
||||
// run throttle and steering controllers
|
||||
calc_steering_to_heading(desired_heading, false); |
||||
calc_throttle(desired_speed, false, true); |
||||
// if sticks in middle, use previous desired heading (important when vehicle is slowing down)
|
||||
if (!is_positive(desired_speed)) { |
||||
desired_heading_cd = _desired_heading_cd; |
||||
} else { |
||||
// record desired heading for next iteration
|
||||
_desired_heading_cd = desired_heading_cd; |
||||
} |
||||
|
||||
// run throttle and steering controllers
|
||||
calc_steering_to_heading(desired_heading_cd, 0.0f, false); |
||||
calc_throttle(desired_speed, false, true); |
||||
} |
||||
|
Loading…
Reference in new issue