mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 19:07:45 +08:00
lib remove extra semicolons
This commit is contained in:
committed by
Nuno Marques
parent
9f44279488
commit
08fbd022af
@@ -53,7 +53,7 @@ public:
|
|||||||
ListNode &operator=(ListNode &&) = delete;
|
ListNode &operator=(ListNode &&) = delete;
|
||||||
|
|
||||||
void setSibling(T sibling) { _sibling = sibling; }
|
void setSibling(T sibling) { _sibling = sibling; }
|
||||||
T getSibling() { return _sibling; }
|
const T getSibling() { return _sibling; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
T _sibling;
|
T _sibling;
|
||||||
@@ -78,7 +78,7 @@ public:
|
|||||||
_head = newNode;
|
_head = newNode;
|
||||||
}
|
}
|
||||||
|
|
||||||
T getHead() { return _head; }
|
const T getHead() { return _head; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
T _head;
|
T _head;
|
||||||
|
|||||||
@@ -65,9 +65,8 @@ public:
|
|||||||
_h(),
|
_h(),
|
||||||
_index(0),
|
_index(0),
|
||||||
_delay(-1)
|
_delay(-1)
|
||||||
{
|
{}
|
||||||
};
|
virtual ~BlockDelay() {}
|
||||||
virtual ~BlockDelay() {};
|
|
||||||
matrix::Matrix<Type, M, N> update(const matrix::Matrix<Type, M, N> &u)
|
matrix::Matrix<Type, M, N> update(const matrix::Matrix<Type, M, N> &u)
|
||||||
{
|
{
|
||||||
// store current value
|
// store current value
|
||||||
|
|||||||
@@ -67,8 +67,8 @@ public:
|
|||||||
_u(0),
|
_u(0),
|
||||||
_initialized(false),
|
_initialized(false),
|
||||||
_lowPass(this, "LP")
|
_lowPass(this, "LP")
|
||||||
{};
|
{}
|
||||||
virtual ~BlockDerivative() {};
|
virtual ~BlockDerivative() {}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Update the state and get current derivative
|
* Update the state and get current derivative
|
||||||
|
|||||||
@@ -68,8 +68,8 @@ public:
|
|||||||
_u(0),
|
_u(0),
|
||||||
_y(0),
|
_y(0),
|
||||||
_fCut(this, "") // only one parameter, no need to name
|
_fCut(this, "") // only one parameter, no need to name
|
||||||
{};
|
{}
|
||||||
virtual ~BlockHighPass() {};
|
virtual ~BlockHighPass() {}
|
||||||
float update(float input);
|
float update(float input);
|
||||||
// accessors
|
// accessors
|
||||||
float getU() {return _u;}
|
float getU() {return _u;}
|
||||||
|
|||||||
@@ -63,8 +63,8 @@ public:
|
|||||||
BlockIntegral(SuperBlock *parent, const char *name) :
|
BlockIntegral(SuperBlock *parent, const char *name) :
|
||||||
SuperBlock(parent, name),
|
SuperBlock(parent, name),
|
||||||
_y(0),
|
_y(0),
|
||||||
_limit(this, "") {};
|
_limit(this, "") {}
|
||||||
virtual ~BlockIntegral() {};
|
virtual ~BlockIntegral() {}
|
||||||
float update(float input);
|
float update(float input);
|
||||||
// accessors
|
// accessors
|
||||||
float getY() {return _y;}
|
float getY() {return _y;}
|
||||||
|
|||||||
@@ -71,8 +71,8 @@ public:
|
|||||||
SuperBlock(parent, name),
|
SuperBlock(parent, name),
|
||||||
_u(0),
|
_u(0),
|
||||||
_y(0),
|
_y(0),
|
||||||
_limit(this, "") {};
|
_limit(this, "") {}
|
||||||
virtual ~BlockIntegralTrap() {};
|
virtual ~BlockIntegralTrap() {}
|
||||||
float update(float input);
|
float update(float input);
|
||||||
// accessors
|
// accessors
|
||||||
float getU() {return _u;}
|
float getU() {return _u;}
|
||||||
|
|||||||
@@ -68,8 +68,8 @@ public:
|
|||||||
Block(parent, name),
|
Block(parent, name),
|
||||||
_min(this, "MIN"),
|
_min(this, "MIN"),
|
||||||
_max(this, "MAX")
|
_max(this, "MAX")
|
||||||
{};
|
{}
|
||||||
virtual ~BlockLimit() {};
|
virtual ~BlockLimit() {}
|
||||||
float update(float input);
|
float update(float input);
|
||||||
// accessors
|
// accessors
|
||||||
float getMin() { return _min.get(); }
|
float getMin() { return _min.get(); }
|
||||||
|
|||||||
@@ -67,8 +67,8 @@ public:
|
|||||||
BlockLimitSym(SuperBlock *parent, const char *name) :
|
BlockLimitSym(SuperBlock *parent, const char *name) :
|
||||||
Block(parent, name),
|
Block(parent, name),
|
||||||
_max(this, "MAX")
|
_max(this, "MAX")
|
||||||
{};
|
{}
|
||||||
virtual ~BlockLimitSym() {};
|
virtual ~BlockLimitSym() {}
|
||||||
float update(float input);
|
float update(float input);
|
||||||
// accessors
|
// accessors
|
||||||
float getMax() { return _max.get(); }
|
float getMax() { return _max.get(); }
|
||||||
|
|||||||
@@ -67,8 +67,8 @@ public:
|
|||||||
Block(parent, name),
|
Block(parent, name),
|
||||||
_state(0.0f / 0.0f /* initialize to invalid val, force into is_finite() check on first call */),
|
_state(0.0f / 0.0f /* initialize to invalid val, force into is_finite() check on first call */),
|
||||||
_fCut(this, "") // only one parameter, no need to name
|
_fCut(this, "") // only one parameter, no need to name
|
||||||
{};
|
{}
|
||||||
virtual ~BlockLowPass() {};
|
virtual ~BlockLowPass() {}
|
||||||
float update(float input);
|
float update(float input);
|
||||||
// accessors
|
// accessors
|
||||||
float getState() { return _state; }
|
float getState() { return _state; }
|
||||||
|
|||||||
@@ -68,8 +68,8 @@ public:
|
|||||||
_fCut(this, ""), // only one parameter, no need to name
|
_fCut(this, ""), // only one parameter, no need to name
|
||||||
_fs(sample_freq),
|
_fs(sample_freq),
|
||||||
_lp(_fs, _fCut.get())
|
_lp(_fs, _fCut.get())
|
||||||
{};
|
{}
|
||||||
virtual ~BlockLowPass2() {};
|
virtual ~BlockLowPass2() {}
|
||||||
float update(float input);
|
float update(float input);
|
||||||
// accessors
|
// accessors
|
||||||
float getState() { return _state; }
|
float getState() { return _state; }
|
||||||
|
|||||||
@@ -69,8 +69,8 @@ public:
|
|||||||
for (int i = 0; i < M; i++) {
|
for (int i = 0; i < M; i++) {
|
||||||
_state(i) = 0.0f / 0.0f;
|
_state(i) = 0.0f / 0.0f;
|
||||||
}
|
}
|
||||||
};
|
}
|
||||||
virtual ~BlockLowPassVector() {};
|
virtual ~BlockLowPassVector() {}
|
||||||
matrix::Vector<Type, M> update(const matrix::Matrix<Type, M, 1> &input)
|
matrix::Vector<Type, M> update(const matrix::Matrix<Type, M, 1> &input)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < M; i++) {
|
for (int i = 0; i < M; i++) {
|
||||||
|
|||||||
@@ -68,8 +68,9 @@ public:
|
|||||||
_val(0)
|
_val(0)
|
||||||
{
|
{
|
||||||
update(0);
|
update(0);
|
||||||
};
|
}
|
||||||
virtual ~BlockOutput() {};
|
|
||||||
|
virtual ~BlockOutput() {}
|
||||||
void update(float input)
|
void update(float input)
|
||||||
{
|
{
|
||||||
_val = _limit.update(input + getTrim());
|
_val = _limit.update(input + getTrim());
|
||||||
|
|||||||
@@ -66,8 +66,8 @@ public:
|
|||||||
BlockP(SuperBlock *parent, const char *name) :
|
BlockP(SuperBlock *parent, const char *name) :
|
||||||
Block(parent, name),
|
Block(parent, name),
|
||||||
_kP(this, "") // only one param, no need to name
|
_kP(this, "") // only one param, no need to name
|
||||||
{};
|
{}
|
||||||
virtual ~BlockP() {};
|
virtual ~BlockP() {}
|
||||||
float update(float input)
|
float update(float input)
|
||||||
{
|
{
|
||||||
return getKP() * input;
|
return getKP() * input;
|
||||||
|
|||||||
@@ -68,8 +68,8 @@ public:
|
|||||||
_derivative(this, "D"),
|
_derivative(this, "D"),
|
||||||
_kP(this, "P"),
|
_kP(this, "P"),
|
||||||
_kD(this, "D")
|
_kD(this, "D")
|
||||||
{};
|
{}
|
||||||
virtual ~BlockPD() {};
|
virtual ~BlockPD() {}
|
||||||
float update(float input)
|
float update(float input)
|
||||||
{
|
{
|
||||||
return getKP() * input +
|
return getKP() * input +
|
||||||
|
|||||||
@@ -68,8 +68,8 @@ public:
|
|||||||
_integral(this, "I"),
|
_integral(this, "I"),
|
||||||
_kP(this, "P"),
|
_kP(this, "P"),
|
||||||
_kI(this, "I")
|
_kI(this, "I")
|
||||||
{};
|
{}
|
||||||
virtual ~BlockPI() {};
|
virtual ~BlockPI() {}
|
||||||
float update(float input)
|
float update(float input)
|
||||||
{
|
{
|
||||||
return getKP() * input +
|
return getKP() * input +
|
||||||
|
|||||||
@@ -70,8 +70,8 @@ public:
|
|||||||
_kP(this, "P"),
|
_kP(this, "P"),
|
||||||
_kI(this, "I"),
|
_kI(this, "I"),
|
||||||
_kD(this, "D")
|
_kD(this, "D")
|
||||||
{};
|
{}
|
||||||
virtual ~BlockPID() {};
|
virtual ~BlockPID() {}
|
||||||
float update(float input)
|
float update(float input)
|
||||||
{
|
{
|
||||||
return getKP() * input +
|
return getKP() * input +
|
||||||
|
|||||||
@@ -68,8 +68,8 @@ public:
|
|||||||
// seed should be initialized somewhere
|
// seed should be initialized somewhere
|
||||||
// in main program for all calls to rand
|
// in main program for all calls to rand
|
||||||
// XXX currently in nuttx if you seed to 0, rand breaks
|
// XXX currently in nuttx if you seed to 0, rand breaks
|
||||||
};
|
}
|
||||||
virtual ~BlockRandGauss() {};
|
virtual ~BlockRandGauss() {}
|
||||||
float update()
|
float update()
|
||||||
{
|
{
|
||||||
static float V1, V2, S;
|
static float V1, V2, S;
|
||||||
|
|||||||
@@ -71,8 +71,8 @@ public:
|
|||||||
// seed should be initialized somewhere
|
// seed should be initialized somewhere
|
||||||
// in main program for all calls to rand
|
// in main program for all calls to rand
|
||||||
// XXX currently in nuttx if you seed to 0, rand breaks
|
// XXX currently in nuttx if you seed to 0, rand breaks
|
||||||
};
|
}
|
||||||
virtual ~BlockRandUniform() {};
|
virtual ~BlockRandUniform() {}
|
||||||
float update()
|
float update()
|
||||||
{
|
{
|
||||||
static float rand_max = RAND_MAX;
|
static float rand_max = RAND_MAX;
|
||||||
|
|||||||
@@ -66,9 +66,8 @@ public:
|
|||||||
_sum(),
|
_sum(),
|
||||||
_sumSq(),
|
_sumSq(),
|
||||||
_count(0)
|
_count(0)
|
||||||
{
|
{}
|
||||||
};
|
virtual ~BlockStats() {}
|
||||||
virtual ~BlockStats() {};
|
|
||||||
void update(const matrix::Vector<Type, M> &u)
|
void update(const matrix::Vector<Type, M> &u)
|
||||||
{
|
{
|
||||||
_sum += u;
|
_sum += u;
|
||||||
|
|||||||
@@ -104,7 +104,7 @@ class __EXPORT SuperBlock :
|
|||||||
public:
|
public:
|
||||||
friend class Block;
|
friend class Block;
|
||||||
|
|
||||||
SuperBlock(SuperBlock *parent, const char *name) : Block(parent, name) {};
|
SuperBlock(SuperBlock *parent, const char *name) : Block(parent, name) {}
|
||||||
~SuperBlock() = default;
|
~SuperBlock() = default;
|
||||||
|
|
||||||
// no copy, assignment, move, move assignment
|
// no copy, assignment, move, move assignment
|
||||||
|
|||||||
@@ -61,7 +61,7 @@ public:
|
|||||||
|
|
||||||
void update(float accel_x);
|
void update(float accel_x);
|
||||||
LaunchDetectionResult getLaunchDetected();
|
LaunchDetectionResult getLaunchDetected();
|
||||||
bool launchDetectionEnabled() { return launchdetection_on.get() == 1; };
|
bool launchDetectionEnabled() { return launchdetection_on.get() == 1; }
|
||||||
|
|
||||||
/* Returns a maximum pitch in deg. Different launch methods may impose upper pitch limits during launch */
|
/* Returns a maximum pitch in deg. Different launch methods may impose upper pitch limits during launch */
|
||||||
float getPitchMax(float pitchMaxDefault);
|
float getPitchMax(float pitchMaxDefault);
|
||||||
|
|||||||
@@ -71,15 +71,15 @@ public:
|
|||||||
void init(float yaw, double current_lat, double current_lon);
|
void init(float yaw, double current_lat, double current_lon);
|
||||||
void update(float airspeed, float alt_agl, double current_lat, double current_lon, orb_advert_t *mavlink_log_pub);
|
void update(float airspeed, float alt_agl, double current_lat, double current_lon, orb_advert_t *mavlink_log_pub);
|
||||||
|
|
||||||
RunwayTakeoffState getState() { return _state; };
|
RunwayTakeoffState getState() { return _state; }
|
||||||
bool isInitialized() { return _initialized; };
|
bool isInitialized() { return _initialized; }
|
||||||
|
|
||||||
bool runwayTakeoffEnabled() { return (bool)_runway_takeoff_enabled.get(); };
|
bool runwayTakeoffEnabled() { return (bool)_runway_takeoff_enabled.get(); }
|
||||||
float getMinAirspeedScaling() { return _min_airspeed_scaling.get(); };
|
float getMinAirspeedScaling() { return _min_airspeed_scaling.get(); }
|
||||||
float getInitYaw() { return _init_yaw; };
|
float getInitYaw() { return _init_yaw; }
|
||||||
|
|
||||||
bool controlYaw();
|
bool controlYaw();
|
||||||
bool climbout() { return _climbout; };
|
bool climbout() { return _climbout; }
|
||||||
float getPitch(float tecsPitch);
|
float getPitch(float tecsPitch);
|
||||||
float getRoll(float navigatorRoll);
|
float getRoll(float navigatorRoll);
|
||||||
float getYaw(float navigatorYaw);
|
float getYaw(float navigatorYaw);
|
||||||
|
|||||||
@@ -58,11 +58,11 @@ class __EXPORT TerrainEstimator
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
TerrainEstimator();
|
TerrainEstimator();
|
||||||
~TerrainEstimator() {};
|
~TerrainEstimator() {}
|
||||||
|
|
||||||
bool is_valid() {return _terrain_valid;}
|
bool is_valid() {return _terrain_valid;}
|
||||||
float get_distance_to_ground() {return -_x(0);}
|
float get_distance_to_ground() {return -_x(0);}
|
||||||
float get_velocity() {return _x(1);};
|
float get_velocity() {return _x(1);}
|
||||||
|
|
||||||
void predict(float dt, const struct vehicle_attitude_s *attitude, const struct sensor_combined_s *sensor,
|
void predict(float dt, const struct vehicle_attitude_s *attitude, const struct sensor_combined_s *sensor,
|
||||||
const struct distance_sensor_s *distance);
|
const struct distance_sensor_s *distance);
|
||||||
|
|||||||
Reference in New Issue
Block a user