mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Sub: Cope with AC_PosControl renaming
This commit is contained in:
parent
b2ef6b901e
commit
27fad4489e
@ -14,8 +14,8 @@ bool Sub::althold_init()
|
|||||||
|
|
||||||
// initialize vertical speeds and leash lengths
|
// initialize vertical speeds and leash lengths
|
||||||
// sets the maximum speed up and down returned by position controller
|
// sets the maximum speed up and down returned by position controller
|
||||||
pos_control.set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
||||||
pos_control.set_accel_z(g.pilot_accel_z);
|
pos_control.set_max_accel_z(g.pilot_accel_z);
|
||||||
|
|
||||||
// initialise position and desired velocity
|
// initialise position and desired velocity
|
||||||
pos_control.set_alt_target(inertial_nav.get_altitude());
|
pos_control.set_alt_target(inertial_nav.get_altitude());
|
||||||
@ -33,8 +33,8 @@ void Sub::althold_run()
|
|||||||
uint32_t tnow = AP_HAL::millis();
|
uint32_t tnow = AP_HAL::millis();
|
||||||
|
|
||||||
// initialize vertical speeds and acceleration
|
// initialize vertical speeds and acceleration
|
||||||
pos_control.set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
||||||
pos_control.set_accel_z(g.pilot_accel_z);
|
pos_control.set_max_accel_z(g.pilot_accel_z);
|
||||||
|
|
||||||
if (!motors.armed()) {
|
if (!motors.armed()) {
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||||
|
@ -653,8 +653,8 @@ bool Sub::auto_terrain_recover_start()
|
|||||||
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
||||||
|
|
||||||
// initialize vertical speeds and leash lengths
|
// initialize vertical speeds and leash lengths
|
||||||
pos_control.set_speed_z(wp_nav.get_speed_down(), wp_nav.get_speed_up());
|
pos_control.set_max_speed_z(wp_nav.get_speed_down(), wp_nav.get_speed_up());
|
||||||
pos_control.set_accel_z(wp_nav.get_accel_z());
|
pos_control.set_max_accel_z(wp_nav.get_accel_z());
|
||||||
|
|
||||||
// Reset vertical position and velocity targets
|
// Reset vertical position and velocity targets
|
||||||
pos_control.set_alt_target(inertial_nav.get_altitude());
|
pos_control.set_alt_target(inertial_nav.get_altitude());
|
||||||
|
@ -14,10 +14,10 @@ bool Sub::circle_init()
|
|||||||
circle_pilot_yaw_override = false;
|
circle_pilot_yaw_override = false;
|
||||||
|
|
||||||
// initialize speeds and accelerations
|
// initialize speeds and accelerations
|
||||||
pos_control.set_speed_xy(wp_nav.get_speed_xy());
|
pos_control.set_max_speed_xy(wp_nav.get_speed_xy());
|
||||||
pos_control.set_accel_xy(wp_nav.get_wp_acceleration());
|
pos_control.set_max_accel_xy(wp_nav.get_wp_acceleration());
|
||||||
pos_control.set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
||||||
pos_control.set_accel_z(g.pilot_accel_z);
|
pos_control.set_max_accel_z(g.pilot_accel_z);
|
||||||
|
|
||||||
// initialise circle controller including setting the circle center based on vehicle speed
|
// initialise circle controller including setting the circle center based on vehicle speed
|
||||||
circle_nav.init();
|
circle_nav.init();
|
||||||
@ -33,10 +33,10 @@ void Sub::circle_run()
|
|||||||
float target_climb_rate = 0;
|
float target_climb_rate = 0;
|
||||||
|
|
||||||
// update parameters, to allow changing at runtime
|
// update parameters, to allow changing at runtime
|
||||||
pos_control.set_speed_xy(wp_nav.get_speed_xy());
|
pos_control.set_max_speed_xy(wp_nav.get_speed_xy());
|
||||||
pos_control.set_accel_xy(wp_nav.get_wp_acceleration());
|
pos_control.set_max_accel_xy(wp_nav.get_wp_acceleration());
|
||||||
pos_control.set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
||||||
pos_control.set_accel_z(g.pilot_accel_z);
|
pos_control.set_max_accel_z(g.pilot_accel_z);
|
||||||
|
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors.armed()) {
|
if (!motors.armed()) {
|
||||||
|
@ -76,8 +76,8 @@ void Sub::guided_vel_control_start()
|
|||||||
guided_mode = Guided_Velocity;
|
guided_mode = Guided_Velocity;
|
||||||
|
|
||||||
// initialize vertical speeds and leash lengths
|
// initialize vertical speeds and leash lengths
|
||||||
pos_control.set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
||||||
pos_control.set_accel_z(g.pilot_accel_z);
|
pos_control.set_max_accel_z(g.pilot_accel_z);
|
||||||
|
|
||||||
// initialise velocity controller
|
// initialise velocity controller
|
||||||
pos_control.init_vel_controller_xyz();
|
pos_control.init_vel_controller_xyz();
|
||||||
@ -92,8 +92,8 @@ void Sub::guided_posvel_control_start()
|
|||||||
pos_control.init_xy_controller();
|
pos_control.init_xy_controller();
|
||||||
|
|
||||||
// set speed and acceleration from wpnav's speed and acceleration
|
// set speed and acceleration from wpnav's speed and acceleration
|
||||||
pos_control.set_speed_xy(wp_nav.get_speed_xy());
|
pos_control.set_max_speed_xy(wp_nav.get_speed_xy());
|
||||||
pos_control.set_accel_xy(wp_nav.get_wp_acceleration());
|
pos_control.set_max_accel_xy(wp_nav.get_wp_acceleration());
|
||||||
|
|
||||||
const Vector3f& curr_pos = inertial_nav.get_position();
|
const Vector3f& curr_pos = inertial_nav.get_position();
|
||||||
const Vector3f& curr_vel = inertial_nav.get_velocity();
|
const Vector3f& curr_vel = inertial_nav.get_velocity();
|
||||||
@ -103,8 +103,8 @@ void Sub::guided_posvel_control_start()
|
|||||||
pos_control.set_desired_velocity_xy(curr_vel.x, curr_vel.y);
|
pos_control.set_desired_velocity_xy(curr_vel.x, curr_vel.y);
|
||||||
|
|
||||||
// set vertical speed and acceleration
|
// set vertical speed and acceleration
|
||||||
pos_control.set_speed_z(wp_nav.get_speed_down(), wp_nav.get_speed_up());
|
pos_control.set_max_speed_z(wp_nav.get_speed_down(), wp_nav.get_speed_up());
|
||||||
pos_control.set_accel_z(wp_nav.get_accel_z());
|
pos_control.set_max_accel_z(wp_nav.get_accel_z());
|
||||||
|
|
||||||
// pilot always controls yaw
|
// pilot always controls yaw
|
||||||
set_auto_yaw_mode(AUTO_YAW_HOLD);
|
set_auto_yaw_mode(AUTO_YAW_HOLD);
|
||||||
@ -117,8 +117,8 @@ void Sub::guided_angle_control_start()
|
|||||||
guided_mode = Guided_Angle;
|
guided_mode = Guided_Angle;
|
||||||
|
|
||||||
// set vertical speed and acceleration
|
// set vertical speed and acceleration
|
||||||
pos_control.set_speed_z(wp_nav.get_speed_down(), wp_nav.get_speed_up());
|
pos_control.set_max_speed_z(wp_nav.get_speed_down(), wp_nav.get_speed_up());
|
||||||
pos_control.set_accel_z(wp_nav.get_accel_z());
|
pos_control.set_max_accel_z(wp_nav.get_accel_z());
|
||||||
|
|
||||||
// initialise position and desired velocity
|
// initialise position and desired velocity
|
||||||
pos_control.set_alt_target(inertial_nav.get_altitude());
|
pos_control.set_alt_target(inertial_nav.get_altitude());
|
||||||
|
@ -15,8 +15,8 @@ bool Sub::poshold_init()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// initialize vertical speeds and acceleration
|
// initialize vertical speeds and acceleration
|
||||||
pos_control.set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
||||||
pos_control.set_accel_z(g.pilot_accel_z);
|
pos_control.set_max_accel_z(g.pilot_accel_z);
|
||||||
|
|
||||||
// initialise position and desired velocity
|
// initialise position and desired velocity
|
||||||
pos_control.set_alt_target(inertial_nav.get_altitude());
|
pos_control.set_alt_target(inertial_nav.get_altitude());
|
||||||
|
@ -8,8 +8,8 @@ bool Sub::surface_init()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// initialize vertical speeds and leash lengths
|
// initialize vertical speeds and leash lengths
|
||||||
pos_control.set_speed_z(wp_nav.get_speed_down(), wp_nav.get_speed_up());
|
pos_control.set_max_speed_z(wp_nav.get_speed_down(), wp_nav.get_speed_up());
|
||||||
pos_control.set_accel_z(wp_nav.get_accel_z());
|
pos_control.set_max_accel_z(wp_nav.get_accel_z());
|
||||||
|
|
||||||
// initialise position and desired velocity
|
// initialise position and desired velocity
|
||||||
pos_control.set_alt_target(inertial_nav.get_altitude());
|
pos_control.set_alt_target(inertial_nav.get_altitude());
|
||||||
@ -48,7 +48,7 @@ void Sub::surface_run()
|
|||||||
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
||||||
|
|
||||||
// set target climb rate
|
// set target climb rate
|
||||||
float cmb_rate = constrain_float(abs(wp_nav.get_speed_up()), 1, pos_control.get_speed_up());
|
float cmb_rate = constrain_float(abs(wp_nav.get_speed_up()), 1, pos_control.get_max_speed_up());
|
||||||
|
|
||||||
// record desired climb rate for logging
|
// record desired climb rate for logging
|
||||||
desired_climb_rate = cmb_rate;
|
desired_climb_rate = cmb_rate;
|
||||||
|
Loading…
Reference in New Issue
Block a user