mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: fixed heli SITL build
This commit is contained in:
parent
14bdfe2889
commit
e5e21ddcce
@ -112,9 +112,6 @@
|
||||
// Local modules
|
||||
#include "Parameters.h"
|
||||
|
||||
// Heli modules
|
||||
#include "heli.h"
|
||||
|
||||
class Copter {
|
||||
public:
|
||||
friend class GCS_MAVLINK;
|
||||
@ -498,6 +495,19 @@ private:
|
||||
// setup the var_info table
|
||||
AP_Param param_loader;
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// Mode filter to reject RC Input glitches. Filter size is 5, and it draws the 4th element, so it can reject 3 low glitches,
|
||||
// and 1 high glitch. This is because any "off" glitches can be highly problematic for a helicopter running an ESC
|
||||
// governor. Even a single "off" frame can cause the rotor to slow dramatically and take a long time to restart.
|
||||
ModeFilterInt16_Size5 rotor_speed_deglitch_filter {4};
|
||||
|
||||
// Tradheli flags
|
||||
struct {
|
||||
uint8_t dynamic_flight : 1; // 0 // true if we are moving at a significant speed (used to turn on/off leaky I terms)
|
||||
uint8_t init_targets_on_arming : 1; // 1 // true if we have been disarmed, and need to reset rate controller targets when we arm
|
||||
} heli_flags;
|
||||
#endif
|
||||
|
||||
static const AP_Scheduler::Task scheduler_tasks[];
|
||||
static const AP_Param::Info var_info[];
|
||||
static const struct LogStructure log_structure[];
|
||||
|
@ -4,8 +4,6 @@
|
||||
|
||||
// Traditional helicopter variables and functions
|
||||
|
||||
#include "heli.h"
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
|
||||
#ifndef HELI_DYNAMIC_FLIGHT_SPEED_MIN
|
||||
|
@ -1,22 +0,0 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#ifndef __HELI_H__
|
||||
#define __HELI_H__
|
||||
|
||||
// Traditional helicopter variables and functions
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
|
||||
// Mode filter to reject RC Input glitches. Filter size is 5, and it draws the 4th element, so it can reject 3 low glitches,
|
||||
// and 1 high glitch. This is because any "off" glitches can be highly problematic for a helicopter running an ESC
|
||||
// governor. Even a single "off" frame can cause the rotor to slow dramatically and take a long time to restart.
|
||||
ModeFilterInt16_Size5 rotor_speed_deglitch_filter(4);
|
||||
|
||||
// Tradheli flags
|
||||
static struct {
|
||||
uint8_t dynamic_flight : 1; // 0 // true if we are moving at a significant speed (used to turn on/off leaky I terms)
|
||||
uint8_t init_targets_on_arming : 1; // 1 // true if we have been disarmed, and need to reset rate controller targets when we arm
|
||||
} heli_flags;
|
||||
|
||||
#endif // FRAME_CONFIG == HELI_FRAME
|
||||
#endif // __HELI_H__
|
Loading…
Reference in New Issue
Block a user