mirror of https://github.com/ArduPilot/ardupilot
Replay: fixed -A0 for "arm immediately"
This commit is contained in:
parent
d3f83e8ec6
commit
b1002eae3b
|
@ -105,7 +105,7 @@ private:
|
||||||
bool done_baro_init;
|
bool done_baro_init;
|
||||||
bool done_home_init;
|
bool done_home_init;
|
||||||
uint16_t update_rate = 50;
|
uint16_t update_rate = 50;
|
||||||
uint32_t arm_time_ms;
|
int32_t arm_time_ms = -1;
|
||||||
bool ahrs_healthy;
|
bool ahrs_healthy;
|
||||||
bool have_imu2;
|
bool have_imu2;
|
||||||
bool have_fram;
|
bool have_fram;
|
||||||
|
@ -217,7 +217,7 @@ void Replay::setup()
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 'A':
|
case 'A':
|
||||||
arm_time_ms = strtoul(optarg, NULL, 0);
|
arm_time_ms = strtol(optarg, NULL, 0);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 'p':
|
case 'p':
|
||||||
|
@ -414,7 +414,7 @@ void Replay::loop()
|
||||||
while (true) {
|
while (true) {
|
||||||
char type[5];
|
char type[5];
|
||||||
|
|
||||||
if (arm_time_ms != 0 && hal.scheduler->millis() > arm_time_ms) {
|
if (arm_time_ms >= 0 && hal.scheduler->millis() > (uint32_t)arm_time_ms) {
|
||||||
if (!hal.util->get_soft_armed()) {
|
if (!hal.util->get_soft_armed()) {
|
||||||
hal.util->set_soft_armed(true);
|
hal.util->set_soft_armed(true);
|
||||||
::printf("Arming at %u ms\n", (unsigned)hal.scheduler->millis());
|
::printf("Arming at %u ms\n", (unsigned)hal.scheduler->millis());
|
||||||
|
|
Loading…
Reference in New Issue