mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: set ahrs flyforward if thr over 15% for 2 seconds
or if throttle is positive and desired speed over 0.5m/s
This commit is contained in:
parent
e691b680ca
commit
73bdc3be09
@ -150,11 +150,8 @@ void Rover::ahrs_update()
|
|||||||
gcs_update();
|
gcs_update();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// when in reverse we need to tell AHRS not to assume we are a
|
// AHRS may use movement to calculate heading
|
||||||
// 'fly forward' vehicle, otherwise it will see a large
|
update_ahrs_flyforward();
|
||||||
// discrepancy between the mag and the GPS heading and will try to
|
|
||||||
// correct for it, leading to a large yaw error
|
|
||||||
ahrs.set_fly_forward(!in_reverse);
|
|
||||||
|
|
||||||
ahrs.update();
|
ahrs.update();
|
||||||
|
|
||||||
|
@ -327,8 +327,8 @@ private:
|
|||||||
// This is the time between calls to the DCM algorithm and is the Integration time for the gyros.
|
// This is the time between calls to the DCM algorithm and is the Integration time for the gyros.
|
||||||
float G_Dt;
|
float G_Dt;
|
||||||
|
|
||||||
// set if we are driving backwards
|
// flyforward timer
|
||||||
bool in_reverse;
|
uint32_t flyforward_start_ms;
|
||||||
|
|
||||||
// true if pivoting (set by use_pivot_steering)
|
// true if pivoting (set by use_pivot_steering)
|
||||||
bool pivot_steering_active;
|
bool pivot_steering_active;
|
||||||
@ -525,7 +525,7 @@ private:
|
|||||||
// system.cpp
|
// system.cpp
|
||||||
void init_ardupilot();
|
void init_ardupilot();
|
||||||
void startup_ground(void);
|
void startup_ground(void);
|
||||||
void set_reverse(bool reverse);
|
void update_ahrs_flyforward();
|
||||||
bool set_mode(Mode &new_mode, mode_reason_t reason);
|
bool set_mode(Mode &new_mode, mode_reason_t reason);
|
||||||
bool mavlink_set_mode(uint8_t mode);
|
bool mavlink_set_mode(uint8_t mode);
|
||||||
void startup_INS_ground(void);
|
void startup_INS_ground(void);
|
||||||
|
@ -420,5 +420,4 @@ void Rover::do_digicam_control(const AP_Mission::Mission_Command& cmd)
|
|||||||
void Rover::do_set_reverse(const AP_Mission::Mission_Command& cmd)
|
void Rover::do_set_reverse(const AP_Mission::Mission_Command& cmd)
|
||||||
{
|
{
|
||||||
mode_auto.set_reversed(cmd.p1 == 1);
|
mode_auto.set_reversed(cmd.p1 == 1);
|
||||||
set_reverse(cmd.p1 == 1);
|
|
||||||
}
|
}
|
||||||
|
@ -11,15 +11,11 @@ void ModeAcro::update()
|
|||||||
get_pilot_desired_steering_and_throttle(desired_steering, desired_throttle);
|
get_pilot_desired_steering_and_throttle(desired_steering, desired_throttle);
|
||||||
// no valid speed, just use the provided throttle
|
// no valid speed, just use the provided throttle
|
||||||
g2.motors.set_throttle(desired_throttle);
|
g2.motors.set_throttle(desired_throttle);
|
||||||
// set reverse flag if negative throttle
|
|
||||||
rover.set_reverse(is_negative(desired_throttle));
|
|
||||||
} else {
|
} else {
|
||||||
float desired_speed;
|
float desired_speed;
|
||||||
// convert pilot stick input into desired steering and speed
|
// convert pilot stick input into desired steering and speed
|
||||||
get_pilot_desired_steering_and_speed(desired_steering, desired_speed);
|
get_pilot_desired_steering_and_speed(desired_steering, desired_speed);
|
||||||
calc_throttle(desired_speed, false, true);
|
calc_throttle(desired_speed, false, true);
|
||||||
// set reverse flag if negative desired speed
|
|
||||||
rover.set_reverse(is_negative(desired_speed));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// convert pilot steering input to desired turn rate in radians/sec
|
// convert pilot steering input to desired turn rate in radians/sec
|
||||||
|
@ -24,9 +24,6 @@ bool ModeAuto::_enter()
|
|||||||
// other initialisation
|
// other initialisation
|
||||||
auto_triggered = false;
|
auto_triggered = false;
|
||||||
|
|
||||||
// initialise reversed to be false
|
|
||||||
set_reversed(false);
|
|
||||||
|
|
||||||
// restart mission processing
|
// restart mission processing
|
||||||
mission.start_or_resume();
|
mission.start_or_resume();
|
||||||
return true;
|
return true;
|
||||||
@ -148,7 +145,6 @@ void ModeAuto::set_reversed(bool value)
|
|||||||
{
|
{
|
||||||
if (_reversed != value) {
|
if (_reversed != value) {
|
||||||
_reversed = value;
|
_reversed = value;
|
||||||
rover.set_reverse(_reversed);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -9,9 +9,6 @@ bool ModeGuided::_enter()
|
|||||||
// when entering guided mode we set the target as the current location.
|
// when entering guided mode we set the target as the current location.
|
||||||
set_desired_location(rover.current_loc);
|
set_desired_location(rover.current_loc);
|
||||||
|
|
||||||
// guided mode never travels in reverse
|
|
||||||
rover.set_reverse(false);
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -6,7 +6,4 @@ void ModeHold::update()
|
|||||||
// hold position - stop motors and center steering
|
// hold position - stop motors and center steering
|
||||||
g2.motors.set_throttle(0.0f);
|
g2.motors.set_throttle(0.0f);
|
||||||
g2.motors.set_steering(0.0f);
|
g2.motors.set_steering(0.0f);
|
||||||
|
|
||||||
// hold mode never reverses
|
|
||||||
rover.set_reverse(false);
|
|
||||||
}
|
}
|
||||||
|
@ -15,9 +15,6 @@ bool ModeLoiter::_enter()
|
|||||||
_desired_yaw_cd = ahrs.yaw_sensor;
|
_desired_yaw_cd = ahrs.yaw_sensor;
|
||||||
_yaw_error_cd = 0.0f;
|
_yaw_error_cd = 0.0f;
|
||||||
|
|
||||||
// set reversed based on speed
|
|
||||||
rover.set_reverse(is_negative(_desired_speed));
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -54,8 +51,4 @@ void ModeLoiter::update()
|
|||||||
// run steering and throttle controllers
|
// run steering and throttle controllers
|
||||||
calc_steering_to_heading(_desired_yaw_cd, _desired_speed < 0);
|
calc_steering_to_heading(_desired_yaw_cd, _desired_speed < 0);
|
||||||
calc_throttle(_desired_speed, false, true);
|
calc_throttle(_desired_speed, false, true);
|
||||||
|
|
||||||
// mark us as in_reverse when using a negative throttle
|
|
||||||
// To-Do: only in reverse if vehicle is actually travelling backwards?
|
|
||||||
rover.set_reverse(_desired_speed < 0);
|
|
||||||
}
|
}
|
||||||
|
@ -9,7 +9,4 @@ void ModeManual::update()
|
|||||||
// copy RC scaled inputs to outputs
|
// copy RC scaled inputs to outputs
|
||||||
g2.motors.set_throttle(desired_throttle);
|
g2.motors.set_throttle(desired_throttle);
|
||||||
g2.motors.set_steering(desired_steering, false);
|
g2.motors.set_steering(desired_steering, false);
|
||||||
|
|
||||||
// mark us as in_reverse when using a negative throttle to stop AHRS getting off
|
|
||||||
rover.set_reverse(is_negative(g2.motors.get_throttle()));
|
|
||||||
}
|
}
|
||||||
|
@ -14,9 +14,6 @@ bool ModeRTL::_enter()
|
|||||||
// set destination
|
// set destination
|
||||||
set_desired_location(rover.home);
|
set_desired_location(rover.home);
|
||||||
|
|
||||||
// RTL never reverses
|
|
||||||
rover.set_reverse(false);
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -20,9 +20,6 @@ bool ModeSmartRTL::_enter()
|
|||||||
// init location target
|
// init location target
|
||||||
set_desired_location(rover.current_loc);
|
set_desired_location(rover.current_loc);
|
||||||
|
|
||||||
// RTL never reverses
|
|
||||||
rover.set_reverse(false);
|
|
||||||
|
|
||||||
// init state
|
// init state
|
||||||
smart_rtl_state = SmartRTL_WaitForPathCleanup;
|
smart_rtl_state = SmartRTL_WaitForPathCleanup;
|
||||||
_reached_destination = false;
|
_reached_destination = false;
|
||||||
|
@ -48,9 +48,6 @@ void ModeSteering::update()
|
|||||||
calc_steering_from_lateral_acceleration(desired_lat_accel, reversed);
|
calc_steering_from_lateral_acceleration(desired_lat_accel, reversed);
|
||||||
}
|
}
|
||||||
|
|
||||||
// mark us as in_reverse when using a negative throttle
|
|
||||||
rover.set_reverse(reversed);
|
|
||||||
|
|
||||||
// run speed to throttle controller
|
// run speed to throttle controller
|
||||||
calc_throttle(desired_speed, false, true);
|
calc_throttle(desired_speed, false, true);
|
||||||
}
|
}
|
||||||
|
@ -203,16 +203,33 @@ void Rover::startup_ground(void)
|
|||||||
gcs().send_text(MAV_SEVERITY_INFO, "Ready to drive");
|
gcs().send_text(MAV_SEVERITY_INFO, "Ready to drive");
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
// update the ahrs flyforward setting which can allow
|
||||||
set the in_reverse flag
|
// the vehicle's movements to be used to estimate heading
|
||||||
reset the throttle integrator if this changes in_reverse
|
void Rover::update_ahrs_flyforward()
|
||||||
*/
|
|
||||||
void Rover::set_reverse(bool reverse)
|
|
||||||
{
|
{
|
||||||
if (in_reverse == reverse) {
|
bool flyforward = false;
|
||||||
return;
|
|
||||||
|
// boats never use movement to estimate heading
|
||||||
|
if (!is_boat()) {
|
||||||
|
// throttle threshold is 15% or 1/2 cruise throttle
|
||||||
|
bool throttle_over_thresh = g2.motors.get_throttle() > MIN(g.throttle_cruise * 0.50f, 15.0f);
|
||||||
|
// desired speed threshold of 1m/s
|
||||||
|
bool desired_speed_over_thresh = g2.attitude_control.speed_control_active() && (g2.attitude_control.get_desired_speed() > 0.5f);
|
||||||
|
if (throttle_over_thresh || (is_positive(g2.motors.get_throttle()) && desired_speed_over_thresh)) {
|
||||||
|
uint32_t now = AP_HAL::millis();
|
||||||
|
// if throttle over threshold start timer
|
||||||
|
if (flyforward_start_ms == 0) {
|
||||||
|
flyforward_start_ms = now;
|
||||||
}
|
}
|
||||||
in_reverse = reverse;
|
// if throttle over threshold for 2 seconds set flyforward to true
|
||||||
|
flyforward = (now - flyforward_start_ms > 2000);
|
||||||
|
} else {
|
||||||
|
// reset timer
|
||||||
|
flyforward_start_ms = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ahrs.set_fly_forward(flyforward);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Rover::set_mode(Mode &new_mode, mode_reason_t reason)
|
bool Rover::set_mode(Mode &new_mode, mode_reason_t reason)
|
||||||
|
Loading…
Reference in New Issue
Block a user