Browse Source

Copter: remove surface tracking shim functions

mission-4.1.18
Randy Mackay 6 years ago
parent
commit
b7d0e4ec10
  1. 16
      ArduCopter/mode.cpp
  2. 3
      ArduCopter/mode.h
  3. 2
      ArduCopter/mode_althold.cpp
  4. 2
      ArduCopter/mode_circle.cpp
  5. 2
      ArduCopter/mode_flowhold.cpp
  6. 2
      ArduCopter/mode_loiter.cpp
  7. 2
      ArduCopter/mode_poshold.cpp
  8. 2
      ArduCopter/mode_sport.cpp
  9. 6
      ArduCopter/mode_zigzag.cpp

16
ArduCopter/mode.cpp

@ -687,22 +687,6 @@ Copter::Mode::AltHoldModeState Copter::Mode::get_alt_hold_state(float target_cli @@ -687,22 +687,6 @@ Copter::Mode::AltHoldModeState Copter::Mode::get_alt_hold_state(float target_cli
// pass-through functions to reduce code churn on conversion;
// these are candidates for moving into the Mode base
// class.
float Copter::Mode::get_surface_tracking_climb_rate(int16_t target_rate)
{
return copter.get_surface_tracking_climb_rate(target_rate);
}
bool Copter::Mode::get_surface_tracking_target_alt_cm(float &target_alt_cm) const
{
return copter.get_surface_tracking_target_alt_cm(target_alt_cm);
}
void Copter::Mode::set_surface_tracking_target_alt_cm(float target_alt_cm)
{
copter.set_surface_tracking_target_alt_cm(target_alt_cm);
}
float Copter::Mode::get_pilot_desired_yaw_rate(int16_t stick_angle)
{
return copter.get_pilot_desired_yaw_rate(stick_angle);

3
ArduCopter/mode.h

@ -197,9 +197,6 @@ protected: @@ -197,9 +197,6 @@ protected:
// pass-through functions to reduce code churn on conversion;
// these are candidates for moving into the Mode base
// class.
float get_surface_tracking_climb_rate(int16_t target_rate);
bool get_surface_tracking_target_alt_cm(float &target_alt_cm) const;
void set_surface_tracking_target_alt_cm(float target_alt_cm);
float get_pilot_desired_yaw_rate(int16_t stick_angle);
float get_pilot_desired_climb_rate(float throttle_control);
float get_pilot_desired_throttle() const;

2
ArduCopter/mode_althold.cpp

@ -96,7 +96,7 @@ void Copter::ModeAltHold::run() @@ -96,7 +96,7 @@ void Copter::ModeAltHold::run()
#endif
// adjust climb rate using rangefinder
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate);
target_climb_rate = copter.get_surface_tracking_climb_rate(target_climb_rate);
// get avoidance adjusted climb rate
target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);

2
ArduCopter/mode_circle.cpp

@ -44,7 +44,7 @@ void Copter::ModeCircle::run() @@ -44,7 +44,7 @@ void Copter::ModeCircle::run()
// adjust climb rate using rangefinder
if (copter.rangefinder_alt_ok()) {
// if rangefinder is ok, use surface tracking
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate);
target_climb_rate = copter.get_surface_tracking_climb_rate(target_climb_rate);
}
// if not armed set throttle to zero and exit immediately

2
ArduCopter/mode_flowhold.cpp

@ -300,7 +300,7 @@ void Copter::ModeFlowHold::run() @@ -300,7 +300,7 @@ void Copter::ModeFlowHold::run()
copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
// adjust climb rate using rangefinder
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate);
target_climb_rate = copter.get_surface_tracking_climb_rate(target_climb_rate);
// get avoidance adjusted climb rate
target_climb_rate = copter.get_avoidance_adjusted_climbrate(target_climb_rate);

2
ArduCopter/mode_loiter.cpp

@ -187,7 +187,7 @@ void Copter::ModeLoiter::run() @@ -187,7 +187,7 @@ void Copter::ModeLoiter::run()
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate);
// adjust climb rate using rangefinder
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate);
target_climb_rate = copter.get_surface_tracking_climb_rate(target_climb_rate);
// get avoidance adjusted climb rate
target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);

2
ArduCopter/mode_poshold.cpp

@ -234,7 +234,7 @@ void Copter::ModePosHold::run() @@ -234,7 +234,7 @@ void Copter::ModePosHold::run()
// adjust climb rate using rangefinder
if (copter.rangefinder_alt_ok()) {
// if rangefinder is ok, use surface tracking
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate);
target_climb_rate = copter.get_surface_tracking_climb_rate(target_climb_rate);
}
// get avoidance adjusted climb rate

2
ArduCopter/mode_sport.cpp

@ -121,7 +121,7 @@ void Copter::ModeSport::run() @@ -121,7 +121,7 @@ void Copter::ModeSport::run()
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
// adjust climb rate using rangefinder
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate);
target_climb_rate = copter.get_surface_tracking_climb_rate(target_climb_rate);
// get avoidance adjusted climb rate
target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);

6
ArduCopter/mode_zigzag.cpp

@ -125,7 +125,7 @@ void Copter::ModeZigZag::return_to_manual_control(bool maintain_target) @@ -125,7 +125,7 @@ void Copter::ModeZigZag::return_to_manual_control(bool maintain_target)
const Vector3f wp_dest = wp_nav->get_wp_destination();
loiter_nav->init_target(wp_dest);
if (maintain_target && wp_nav->origin_and_destination_are_terrain_alt()) {
set_surface_tracking_target_alt_cm(wp_dest.z);
copter.set_surface_tracking_target_alt_cm(wp_dest.z);
}
gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: manual control");
}
@ -200,7 +200,7 @@ void Copter::ModeZigZag::manual_control() @@ -200,7 +200,7 @@ void Copter::ModeZigZag::manual_control()
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate);
// adjust climb rate using rangefinder
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate);
target_climb_rate = copter.get_surface_tracking_climb_rate(target_climb_rate);
// get avoidance adjusted climb rate
target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
@ -283,7 +283,7 @@ bool Copter::ModeZigZag::calculate_next_dest(uint8_t dest_num, bool use_wpnav_al @@ -283,7 +283,7 @@ bool Copter::ModeZigZag::calculate_next_dest(uint8_t dest_num, bool use_wpnav_al
// if we have a downward facing range finder then use terrain altitude targets
terrain_alt = copter.rangefinder_alt_ok() && wp_nav->rangefinder_used();
if (terrain_alt) {
if (!get_surface_tracking_target_alt_cm(next_dest.z)) {
if (!copter.get_surface_tracking_target_alt_cm(next_dest.z)) {
next_dest.z = copter.rangefinder_state.alt_cm_filt.get();
}
} else {

Loading…
Cancel
Save