APM:Libraries
AC_PosControl_Sub.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AC_PosControl.h"
4 
6 public:
8  const AP_Motors& motors, AC_AttitudeControl& attitude_control);
9 
13  void set_alt_max(float alt) { _alt_max = alt; }
14 
18  void set_alt_min(float alt) { _alt_min = alt; }
19 
25  void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend) override;
26 
32  void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend) override;
33 
34 private:
35  float _alt_max; // max altitude - should be updated from the main code with altitude limit from fence
36  float _alt_min; // min altitude - should be updated from the main code with altitude limit from fence
37 };
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
AP_MotorsMatrix motors(400)
void set_alt_min(float alt)
void set_alt_max(float alt)
void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend) override
void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend) override
AC_PosControl_Sub(const AP_AHRS_View &ahrs, const AP_InertialNav &inav, const AP_Motors &motors, AC_AttitudeControl &attitude_control)