Skip to content

Commit

Permalink
SITL: Fix missing newline
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Oct 31, 2023
1 parent 250fbef commit 173500a
Showing 1 changed file with 44 additions and 44 deletions.
88 changes: 44 additions & 44 deletions libraries/SITL/SITL_Airspeed.cpp
Original file line number Diff line number Diff line change
@@ -1,44 +1,44 @@
#include "SITL.h"

#if AP_SIM_ENABLED

namespace SITL {
// user settable parameters for airspeed sensors
const AP_Param::GroupInfo SIM::AirspeedParm::var_info[] = {
// user settable parameters for the 1st airspeed sensor
AP_GROUPINFO("RND", 1, AirspeedParm, noise, 2.0),
AP_GROUPINFO("OFS", 2, AirspeedParm, offset, 2013),
// @Param: FAIL
// @DisplayName: Airspeed sensor failure
// @Description: Simulates Airspeed sensor 1 failure
// @Values: 0:Disabled, 1:Enabled
// @User: Advanced
AP_GROUPINFO("FAIL", 3, AirspeedParm, fail, 0),
// @Param: FAILP
// @DisplayName: Airspeed sensor failure pressure
// @Description: Simulated airspeed sensor failure pressure
// @Units: Pa
// @User: Advanced
AP_GROUPINFO("FAILP", 4, AirspeedParm, fail_pressure, 0),
// @Param: PITOT
// @DisplayName: Airspeed pitot tube failure pressure
// @Description: Simulated airspeed sensor pitot tube failure pressure
// @Units: Pa
// @User: Advanced
AP_GROUPINFO("PITOT", 5, AirspeedParm, fail_pitot_pressure, 0),
// @Param: SIGN
// @DisplayName: Airspeed signflip
// @Description: Simulated airspeed sensor with reversed pitot/static connections
// @Values: 0:Disabled, 1:Enabled
// @User: Advanced
AP_GROUPINFO("SIGN", 6, AirspeedParm, signflip, 0),
// @Param: RATIO
// @DisplayName: Airspeed ratios
// @Description: Simulated airspeed sensor ratio
// @User: Advanced
AP_GROUPINFO("RATIO", 7, AirspeedParm, ratio, 1.99),
AP_GROUPEND
};
}

#endif // AP_SIM_ENABLED
#include "SITL.h"

#if AP_SIM_ENABLED

namespace SITL {
// user settable parameters for airspeed sensors
const AP_Param::GroupInfo SIM::AirspeedParm::var_info[] = {
// user settable parameters for the 1st airspeed sensor
AP_GROUPINFO("RND", 1, AirspeedParm, noise, 2.0),
AP_GROUPINFO("OFS", 2, AirspeedParm, offset, 2013),
// @Param: FAIL
// @DisplayName: Airspeed sensor failure
// @Description: Simulates Airspeed sensor 1 failure
// @Values: 0:Disabled, 1:Enabled
// @User: Advanced
AP_GROUPINFO("FAIL", 3, AirspeedParm, fail, 0),
// @Param: FAILP
// @DisplayName: Airspeed sensor failure pressure
// @Description: Simulated airspeed sensor failure pressure
// @Units: Pa
// @User: Advanced
AP_GROUPINFO("FAILP", 4, AirspeedParm, fail_pressure, 0),
// @Param: PITOT
// @DisplayName: Airspeed pitot tube failure pressure
// @Description: Simulated airspeed sensor pitot tube failure pressure
// @Units: Pa
// @User: Advanced
AP_GROUPINFO("PITOT", 5, AirspeedParm, fail_pitot_pressure, 0),
// @Param: SIGN
// @DisplayName: Airspeed signflip
// @Description: Simulated airspeed sensor with reversed pitot/static connections
// @Values: 0:Disabled, 1:Enabled
// @User: Advanced
AP_GROUPINFO("SIGN", 6, AirspeedParm, signflip, 0),
// @Param: RATIO
// @DisplayName: Airspeed ratios
// @Description: Simulated airspeed sensor ratio
// @User: Advanced
AP_GROUPINFO("RATIO", 7, AirspeedParm, ratio, 1.99),
AP_GROUPEND
};
}

#endif // AP_SIM_ENABLED

0 comments on commit 173500a

Please sign in to comment.