forked from Archive/PX4-Autopilot
SITL: enable failure command (SYS_FAILURE_EN=1)
This commit is contained in:
parent
56faaae959
commit
8bf18e31be
|
@ -154,6 +154,8 @@ param set-default SDLOG_DIRS_MAX 7
|
|||
|
||||
param set-default TRIG_INTERFACE 3
|
||||
|
||||
param set-default SYS_FAILURE_EN 1
|
||||
|
||||
# Adapt timeout parameters if simulation runs faster or slower than realtime.
|
||||
if [ -n "$PX4_SIM_SPEED_FACTOR" ]; then
|
||||
COM_DL_LOSS_T_LONGER=$(echo "$PX4_SIM_SPEED_FACTOR * 10" | bc)
|
||||
|
|
|
@ -139,6 +139,11 @@ public:
|
|||
// Blocking call to get the drone's current position in NED frame
|
||||
std::array<float, 3> get_current_position_ned();
|
||||
|
||||
void set_param_int(const std::string ¶m, int32_t value)
|
||||
{
|
||||
CHECK(_param->set_param_int(param, value) == Param::Result::Success);
|
||||
}
|
||||
|
||||
protected:
|
||||
mavsdk::Param *getParams() const { return _param.get();}
|
||||
mavsdk::Telemetry *getTelemetry() const { return _telemetry.get();}
|
||||
|
|
|
@ -41,6 +41,7 @@ TEST_CASE("Failure Injection - Reject mid-air when it is disabled", "[multicopte
|
|||
AutopilotTesterFailure tester;
|
||||
tester.connect(connection_url);
|
||||
tester.wait_until_ready();
|
||||
tester.set_param_int("SYS_FAILURE_EN", 0);
|
||||
tester.arm();
|
||||
tester.takeoff();
|
||||
tester.wait_until_hovering();
|
||||
|
|
Loading…
Reference in New Issue