mirror of https://github.com/ArduPilot/ardupilot
Rover: removed some more plane specific variables
This commit is contained in:
parent
ebafad7a6b
commit
e924460881
|
@ -14,24 +14,3 @@
|
||||||
|
|
||||||
#define TRACE DISABLED
|
#define TRACE DISABLED
|
||||||
|
|
||||||
//#define LOGGING_ENABLED DISABLED
|
|
||||||
|
|
||||||
//#include "APM_Config_HILmode.h" // for test in HIL mode with AeroSIM Rc 3.83
|
|
||||||
//#include "APM_Config_Rover.h" // to be used with the real Traxxas model Monster Jam Grinder
|
|
||||||
|
|
||||||
// Radio setup:
|
|
||||||
// APM INPUT (Rec = receiver)
|
|
||||||
// Rec ch1: Roll
|
|
||||||
// Rec ch2: Throttle
|
|
||||||
// Rec ch3: Pitch
|
|
||||||
// Rec ch4: Yaw
|
|
||||||
// Rec ch5: not used
|
|
||||||
// Rec ch6:
|
|
||||||
// Rec ch7: Option channel to 2 positions switch
|
|
||||||
// Rec ch8: Mode channel to 3 positions switch
|
|
||||||
// APM OUTPUT
|
|
||||||
// Ch1: Wheel servo (direction)
|
|
||||||
// Ch2: not used
|
|
||||||
// Ch3: to the motor ESC
|
|
||||||
// Ch4: not used
|
|
||||||
|
|
||||||
|
|
|
@ -354,9 +354,7 @@ static int16_t failsafe;
|
||||||
// Used to track if the value on channel 3 (throtttle) has fallen below the failsafe threshold
|
// Used to track if the value on channel 3 (throtttle) has fallen below the failsafe threshold
|
||||||
// RC receiver should be set up to output a low throttle value when signal is lost
|
// RC receiver should be set up to output a low throttle value when signal is lost
|
||||||
static bool ch3_failsafe;
|
static bool ch3_failsafe;
|
||||||
// A timer used to help recovery from unusual attitudes. If we enter an unusual attitude
|
|
||||||
// while in autonomous flight this variable is used to hold roll at 0 for a recovery period
|
|
||||||
static byte crash_timer;
|
|
||||||
// A timer used to track how long since we have received the last GCS heartbeat or rc override message
|
// A timer used to track how long since we have received the last GCS heartbeat or rc override message
|
||||||
static uint32_t rc_override_fs_timer = 0;
|
static uint32_t rc_override_fs_timer = 0;
|
||||||
// A timer used to track how long we have been in a "short failsafe" condition due to loss of RC signal
|
// A timer used to track how long we have been in a "short failsafe" condition due to loss of RC signal
|
||||||
|
@ -481,8 +479,6 @@ static bool speed_boost = false;
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// The instantaneous desired bank angle. Hundredths of a degree
|
// The instantaneous desired bank angle. Hundredths of a degree
|
||||||
static int32_t nav_roll;
|
static int32_t nav_roll;
|
||||||
// The instantaneous desired pitch angle. Hundredths of a degree
|
|
||||||
static int32_t nav_pitch;
|
|
||||||
// Calculated radius for the wp turn based on ground speed and max turn angle
|
// Calculated radius for the wp turn based on ground speed and max turn angle
|
||||||
static int32_t wp_radius;
|
static int32_t wp_radius;
|
||||||
|
|
||||||
|
@ -935,7 +931,6 @@ static void update_current_flight_mode(void)
|
||||||
case LEARNING:
|
case LEARNING:
|
||||||
case MANUAL:
|
case MANUAL:
|
||||||
nav_roll = 0;
|
nav_roll = 0;
|
||||||
nav_pitch = 0;
|
|
||||||
g.channel_roll.servo_out = g.channel_roll.pwm_to_angle();
|
g.channel_roll.servo_out = g.channel_roll.pwm_to_angle();
|
||||||
g.channel_pitch.servo_out = g.channel_pitch.pwm_to_angle();
|
g.channel_pitch.servo_out = g.channel_pitch.pwm_to_angle();
|
||||||
g.channel_rudder.servo_out = g.channel_roll.pwm_to_angle();
|
g.channel_rudder.servo_out = g.channel_roll.pwm_to_angle();
|
||||||
|
@ -945,17 +940,14 @@ static void update_current_flight_mode(void)
|
||||||
|
|
||||||
static void update_navigation()
|
static void update_navigation()
|
||||||
{
|
{
|
||||||
// wp_distance is in ACTUAL meters, not the *100 meters we get from the GPS
|
|
||||||
// ------------------------------------------------------------------------
|
|
||||||
|
|
||||||
// distance and bearing calcs only
|
|
||||||
if(control_mode == AUTO){
|
|
||||||
verify_commands();
|
|
||||||
}else{
|
|
||||||
|
|
||||||
switch (control_mode) {
|
switch (control_mode) {
|
||||||
case RTL: // no loitering around the wp with the rover, goes direct to the wp position
|
case AUTO:
|
||||||
|
verify_commands();
|
||||||
|
break;
|
||||||
|
|
||||||
|
case RTL:
|
||||||
case GUIDED:
|
case GUIDED:
|
||||||
|
// no loitering around the wp with the rover, goes direct to the wp position
|
||||||
calc_nav_roll();
|
calc_nav_roll();
|
||||||
calc_bearing_error();
|
calc_bearing_error();
|
||||||
if(verify_RTL()) {
|
if(verify_RTL()) {
|
||||||
|
@ -963,7 +955,5 @@ static void update_navigation()
|
||||||
set_mode(MANUAL);
|
set_mode(MANUAL);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -54,7 +54,6 @@ static void calc_throttle()
|
||||||
|
|
||||||
static void calc_nav_roll()
|
static void calc_nav_roll()
|
||||||
{
|
{
|
||||||
|
|
||||||
// Adjust gain based on ground speed
|
// Adjust gain based on ground speed
|
||||||
nav_gain_scaler = (float)ground_speed / (g.airspeed_cruise * 100.0);
|
nav_gain_scaler = (float)ground_speed / (g.airspeed_cruise * 100.0);
|
||||||
nav_gain_scaler = constrain(nav_gain_scaler, 0.2, 1.4);
|
nav_gain_scaler = constrain(nav_gain_scaler, 0.2, 1.4);
|
||||||
|
@ -72,7 +71,6 @@ static void calc_nav_roll()
|
||||||
speed_boost = false;
|
speed_boost = false;
|
||||||
}
|
}
|
||||||
nav_roll = constrain(nav_roll, -g.roll_limit.get(), g.roll_limit.get());
|
nav_roll = constrain(nav_roll, -g.roll_limit.get(), g.roll_limit.get());
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Zeros out navigation Integrators if we are changing mode, have passed a waypoint, etc.
|
// Zeros out navigation Integrators if we are changing mode, have passed a waypoint, etc.
|
||||||
|
@ -81,7 +79,6 @@ static void reset_I(void)
|
||||||
{
|
{
|
||||||
g.pidNavRoll.reset_I();
|
g.pidNavRoll.reset_I();
|
||||||
g.pidTeThrottle.reset_I();
|
g.pidTeThrottle.reset_I();
|
||||||
// g.pidAltitudeThrottle.reset_I();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*****************************************
|
/*****************************************
|
||||||
|
|
|
@ -218,7 +218,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
||||||
mavlink_msg_nav_controller_output_send(
|
mavlink_msg_nav_controller_output_send(
|
||||||
chan,
|
chan,
|
||||||
nav_roll / 1.0e2,
|
nav_roll / 1.0e2,
|
||||||
nav_pitch / 1.0e2,
|
0,
|
||||||
bearing,
|
bearing,
|
||||||
target_bearing / 100,
|
target_bearing / 100,
|
||||||
wp_distance,
|
wp_distance,
|
||||||
|
|
|
@ -304,7 +304,7 @@ static void Log_Write_Control_Tuning()
|
||||||
DataFlash.WriteInt((int)nav_roll);
|
DataFlash.WriteInt((int)nav_roll);
|
||||||
DataFlash.WriteInt((int)ahrs.roll_sensor);
|
DataFlash.WriteInt((int)ahrs.roll_sensor);
|
||||||
DataFlash.WriteInt((int)(g.channel_pitch.servo_out));
|
DataFlash.WriteInt((int)(g.channel_pitch.servo_out));
|
||||||
DataFlash.WriteInt((int)nav_pitch);
|
DataFlash.WriteInt(0); // nav_pitch
|
||||||
DataFlash.WriteInt((int)ahrs.pitch_sensor);
|
DataFlash.WriteInt((int)ahrs.pitch_sensor);
|
||||||
DataFlash.WriteInt((int)(g.channel_throttle.servo_out));
|
DataFlash.WriteInt((int)(g.channel_throttle.servo_out));
|
||||||
DataFlash.WriteInt((int)(g.channel_rudder.servo_out));
|
DataFlash.WriteInt((int)(g.channel_rudder.servo_out));
|
||||||
|
|
|
@ -174,7 +174,6 @@ static void do_RTL(void)
|
||||||
{
|
{
|
||||||
prev_WP = current_loc;
|
prev_WP = current_loc;
|
||||||
control_mode = RTL;
|
control_mode = RTL;
|
||||||
crash_timer = 0;
|
|
||||||
next_WP = home;
|
next_WP = home;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -364,7 +364,6 @@ static void set_mode(byte mode)
|
||||||
trim_control_surfaces();
|
trim_control_surfaces();
|
||||||
|
|
||||||
control_mode = mode;
|
control_mode = mode;
|
||||||
crash_timer = 0;
|
|
||||||
throttle_last = 0;
|
throttle_last = 0;
|
||||||
throttle = 500;
|
throttle = 500;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue