mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_TECS: reformat using astyle
This commit is contained in:
parent
86e8c7ed2f
commit
094b9cb35e
@ -6,10 +6,10 @@
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include <stdio.h>
|
||||
# define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
|
||||
#include <stdio.h>
|
||||
# define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
|
||||
#else
|
||||
# define Debug(fmt, args ...)
|
||||
# define Debug(fmt, args ...)
|
||||
#endif
|
||||
//Debug("%.2f %.2f %.2f %.2f \n", var1, var2, var3, var4);
|
||||
|
||||
@ -332,7 +332,7 @@ void AP_TECS::_update_speed(float load_factor)
|
||||
float aspdErr = (_EAS * EAS2TAS) - _integ5_state;
|
||||
float integ4_input = aspdErr * _spdCompFiltOmega * _spdCompFiltOmega;
|
||||
// Prevent state from winding up
|
||||
if (_integ5_state < 3.1f){
|
||||
if (_integ5_state < 3.1f) {
|
||||
integ4_input = max(integ4_input , 0.0f);
|
||||
}
|
||||
_integ4_state = _integ4_state + integ4_input * DT;
|
||||
|
@ -1,4 +1,4 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
/// @file AP_TECS.h
|
||||
/// @brief Combined Total Energy Speed & Height Control. This is a instance of an
|
||||
@ -54,26 +54,38 @@ public:
|
||||
|
||||
// demanded throttle in percentage
|
||||
// should return 0 to 100
|
||||
int32_t get_throttle_demand(void) {return int32_t(_throttle_dem * 100.0f);}
|
||||
int32_t get_throttle_demand(void) {
|
||||
return int32_t(_throttle_dem * 100.0f);
|
||||
}
|
||||
|
||||
// demanded pitch angle in centi-degrees
|
||||
// should return between -9000 to +9000
|
||||
int32_t get_pitch_demand(void) { return int32_t(_pitch_dem * 5729.5781f);}
|
||||
int32_t get_pitch_demand(void) {
|
||||
return int32_t(_pitch_dem * 5729.5781f);
|
||||
}
|
||||
|
||||
// Rate of change of velocity along X body axis in m/s^2
|
||||
float get_VXdot(void) { return _vel_dot; }
|
||||
float get_VXdot(void) {
|
||||
return _vel_dot;
|
||||
}
|
||||
|
||||
// log data on internal state of the controller. Called at 10Hz
|
||||
void log_data(DataFlash_Class &dataflash, uint8_t msgid);
|
||||
|
||||
// return current target airspeed
|
||||
float get_target_airspeed(void) const { return _TAS_dem / _ahrs.get_EAS2TAS(); }
|
||||
float get_target_airspeed(void) const {
|
||||
return _TAS_dem / _ahrs.get_EAS2TAS();
|
||||
}
|
||||
|
||||
// return maximum climb rate
|
||||
float get_max_climbrate(void) const { return _maxClimbRate; }
|
||||
float get_max_climbrate(void) const {
|
||||
return _maxClimbRate;
|
||||
}
|
||||
|
||||
// return landing sink rate
|
||||
float get_land_sinkrate(void) const { return _land_sink; }
|
||||
float get_land_sinkrate(void) const {
|
||||
return _land_sink;
|
||||
}
|
||||
|
||||
// this supports the TECS_* user settable parameters
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
Loading…
Reference in New Issue
Block a user