mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: move all of waypoint-takeoff into Mode namespace
This commit is contained in:
parent
11aeec6dd1
commit
22f7f29045
@ -365,8 +365,6 @@ private:
|
|||||||
uint8_t count;
|
uint8_t count;
|
||||||
uint8_t ch_flag;
|
uint8_t ch_flag;
|
||||||
} aux_debounce[(CH_12 - CH_7)+1];
|
} aux_debounce[(CH_12 - CH_7)+1];
|
||||||
// altitude below which we do no navigation in auto takeoff
|
|
||||||
float auto_takeoff_no_nav_alt_cm;
|
|
||||||
|
|
||||||
RCMapper rcmap;
|
RCMapper rcmap;
|
||||||
|
|
||||||
@ -919,9 +917,6 @@ private:
|
|||||||
const char* get_frame_string();
|
const char* get_frame_string();
|
||||||
void allocate_motors(void);
|
void allocate_motors(void);
|
||||||
|
|
||||||
void auto_takeoff_set_start_alt(void);
|
|
||||||
void auto_takeoff_attitude_run(float target_yaw_rate);
|
|
||||||
|
|
||||||
// terrain.cpp
|
// terrain.cpp
|
||||||
void terrain_update();
|
void terrain_update();
|
||||||
void terrain_logging();
|
void terrain_logging();
|
||||||
|
@ -31,6 +31,8 @@ Copter::Mode::Mode(void) :
|
|||||||
ekfNavVelGainScaler(copter.ekfNavVelGainScaler)
|
ekfNavVelGainScaler(copter.ekfNavVelGainScaler)
|
||||||
{ };
|
{ };
|
||||||
|
|
||||||
|
float Copter::Mode::auto_takeoff_no_nav_alt_cm = 0;
|
||||||
|
|
||||||
// return the static controller object corresponding to supplied mode
|
// return the static controller object corresponding to supplied mode
|
||||||
Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
|
Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
|
||||||
{
|
{
|
||||||
|
@ -160,6 +160,10 @@ protected:
|
|||||||
// method shared by both Guided and Auto for takeoff. This is
|
// method shared by both Guided and Auto for takeoff. This is
|
||||||
// waypoint navigation but the user can control the yaw.
|
// waypoint navigation but the user can control the yaw.
|
||||||
void auto_takeoff_run();
|
void auto_takeoff_run();
|
||||||
|
void auto_takeoff_set_start_alt(void);
|
||||||
|
void auto_takeoff_attitude_run(float target_yaw_rate);
|
||||||
|
// altitude below which we do no navigation in auto takeoff
|
||||||
|
static float auto_takeoff_no_nav_alt_cm;
|
||||||
|
|
||||||
// gnd speed limit required to observe optical flow sensor limits
|
// gnd speed limit required to observe optical flow sensor limits
|
||||||
float &ekfGndSpdLimit;
|
float &ekfGndSpdLimit;
|
||||||
|
@ -176,7 +176,7 @@ void Copter::ModeAuto::takeoff_start(const Location& dest_loc)
|
|||||||
set_throttle_takeoff();
|
set_throttle_takeoff();
|
||||||
|
|
||||||
// get initial alt for WP_NAVALT_MIN
|
// get initial alt for WP_NAVALT_MIN
|
||||||
copter.auto_takeoff_set_start_alt();
|
auto_takeoff_set_start_alt();
|
||||||
}
|
}
|
||||||
|
|
||||||
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
|
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
|
||||||
|
@ -71,7 +71,7 @@ bool Copter::ModeGuided::do_user_takeoff_start(float final_alt_above_home)
|
|||||||
set_throttle_takeoff();
|
set_throttle_takeoff();
|
||||||
|
|
||||||
// get initial alt for WP_NAVALT_MIN
|
// get initial alt for WP_NAVALT_MIN
|
||||||
copter.auto_takeoff_set_start_alt();
|
auto_takeoff_set_start_alt();
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -409,7 +409,7 @@ void Copter::Mode::auto_takeoff_run()
|
|||||||
copter.pos_control->update_z_controller();
|
copter.pos_control->update_z_controller();
|
||||||
|
|
||||||
// call attitude controller
|
// call attitude controller
|
||||||
copter.auto_takeoff_attitude_run(target_yaw_rate);
|
auto_takeoff_attitude_run(target_yaw_rate);
|
||||||
}
|
}
|
||||||
|
|
||||||
// guided_pos_control_run - runs the guided position controller
|
// guided_pos_control_run - runs the guided position controller
|
||||||
|
@ -135,7 +135,7 @@ void Copter::Mode::_TakeOff::get_climb_rates(float& pilot_climb_rate,
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void Copter::auto_takeoff_set_start_alt(void)
|
void Copter::Mode::auto_takeoff_set_start_alt(void)
|
||||||
{
|
{
|
||||||
// start with our current altitude
|
// start with our current altitude
|
||||||
auto_takeoff_no_nav_alt_cm = inertial_nav.get_altitude();
|
auto_takeoff_no_nav_alt_cm = inertial_nav.get_altitude();
|
||||||
@ -151,7 +151,7 @@ void Copter::auto_takeoff_set_start_alt(void)
|
|||||||
call attitude controller for automatic takeoff, limiting roll/pitch
|
call attitude controller for automatic takeoff, limiting roll/pitch
|
||||||
if below wp_navalt_min
|
if below wp_navalt_min
|
||||||
*/
|
*/
|
||||||
void Copter::auto_takeoff_attitude_run(float target_yaw_rate)
|
void Copter::Mode::auto_takeoff_attitude_run(float target_yaw_rate)
|
||||||
{
|
{
|
||||||
float nav_roll, nav_pitch;
|
float nav_roll, nav_pitch;
|
||||||
|
|
||||||
@ -161,7 +161,7 @@ void Copter::auto_takeoff_attitude_run(float target_yaw_rate)
|
|||||||
nav_pitch = 0;
|
nav_pitch = 0;
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
// prevent hover roll starting till past specified altitude
|
// prevent hover roll starting till past specified altitude
|
||||||
hover_roll_trim_scalar_slew = 0;
|
copter.hover_roll_trim_scalar_slew = 0;
|
||||||
#endif
|
#endif
|
||||||
// tell the position controller that we have limited roll/pitch demand to prevent integrator buildup
|
// tell the position controller that we have limited roll/pitch demand to prevent integrator buildup
|
||||||
pos_control->set_limit_accel_xy();
|
pos_control->set_limit_accel_xy();
|
||||||
|
Loading…
Reference in New Issue
Block a user