mirror of https://github.com/ArduPilot/ardupilot
Rover: Whitespace/formatting change ONLY for Steering.cpp
This commit is contained in:
parent
bbbbd07935
commit
039ea59d7e
|
@ -3,10 +3,9 @@
|
|||
#include "Rover.h"
|
||||
|
||||
/*****************************************
|
||||
* Throttle slew limit
|
||||
Throttle slew limit
|
||||
*****************************************/
|
||||
void Rover::throttle_slew_limit(int16_t last_throttle)
|
||||
{
|
||||
void Rover::throttle_slew_limit(int16_t last_throttle) {
|
||||
// if slew limit rate is set to zero then do not slew limit
|
||||
if (g.throttle_slewrate && last_throttle != 0) {
|
||||
// limit throttle change by the given percentage per second
|
||||
|
@ -22,8 +21,7 @@ void Rover::throttle_slew_limit(int16_t last_throttle)
|
|||
/*
|
||||
check for triggering of start of auto mode
|
||||
*/
|
||||
bool Rover::auto_check_trigger(void)
|
||||
{
|
||||
bool Rover::auto_check_trigger(void) {
|
||||
// only applies to AUTO mode
|
||||
if (control_mode != AUTO) {
|
||||
return true;
|
||||
|
@ -69,8 +67,7 @@ bool Rover::auto_check_trigger(void)
|
|||
/*
|
||||
work out if we are going to use pivot steering
|
||||
*/
|
||||
bool Rover::use_pivot_steering(void)
|
||||
{
|
||||
bool Rover::use_pivot_steering(void) {
|
||||
if (control_mode >= AUTO && g.skid_steer_out && g.pivot_turn_angle != 0) {
|
||||
int16_t bearing_error = wrap_180_cd(nav_controller->target_bearing_cd() - ahrs.yaw_sensor) / 100;
|
||||
if (abs(bearing_error) > g.pivot_turn_angle) {
|
||||
|
@ -84,8 +81,7 @@ bool Rover::use_pivot_steering(void)
|
|||
/*
|
||||
calculate the throtte for auto-throttle modes
|
||||
*/
|
||||
void Rover::calc_throttle(float target_speed)
|
||||
{
|
||||
void Rover::calc_throttle(float target_speed) {
|
||||
// If not autostarting OR we are loitering at a waypoint
|
||||
// then set the throttle to minimum
|
||||
if (!auto_check_trigger() || ((loiter_time > 0) && (control_mode == AUTO))) {
|
||||
|
@ -159,11 +155,10 @@ void Rover::calc_throttle(float target_speed)
|
|||
}
|
||||
|
||||
/*****************************************
|
||||
* Calculate desired turn angles (in medium freq loop)
|
||||
Calculate desired turn angles (in medium freq loop)
|
||||
*****************************************/
|
||||
|
||||
void Rover::calc_lateral_acceleration()
|
||||
{
|
||||
void Rover::calc_lateral_acceleration() {
|
||||
switch (control_mode) {
|
||||
case AUTO:
|
||||
nav_controller->update_waypoint(prev_WP, next_WP);
|
||||
|
@ -196,8 +191,7 @@ void Rover::calc_lateral_acceleration()
|
|||
/*
|
||||
calculate steering angle given lateral_acceleration
|
||||
*/
|
||||
void Rover::calc_nav_steer()
|
||||
{
|
||||
void Rover::calc_nav_steer() {
|
||||
// check to see if the rover is loitering
|
||||
if ((loiter_time > 0) && (control_mode == AUTO)) {
|
||||
channel_steer->servo_out = 0;
|
||||
|
@ -214,10 +208,9 @@ void Rover::calc_nav_steer()
|
|||
}
|
||||
|
||||
/*****************************************
|
||||
* Set the flight control servos based on the current calculated values
|
||||
Set the flight control servos based on the current calculated values
|
||||
*****************************************/
|
||||
void Rover::set_servos(void)
|
||||
{
|
||||
void Rover::set_servos(void) {
|
||||
static int16_t last_throttle;
|
||||
|
||||
// support a separate steering channel
|
||||
|
|
Loading…
Reference in New Issue