mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Fixed APO bug in current waypoint update.
This commit is contained in:
parent
fc12113167
commit
9192143c44
1
.gitignore
vendored
1
.gitignore
vendored
@ -17,3 +17,4 @@ build
|
||||
/Tools/ArdupilotMegaPlanner/obj
|
||||
/Tools/ArdupilotMegaPlanner/resedit/bin
|
||||
/Tools/ArdupilotMegaPlanner/resedit/obj
|
||||
tags
|
||||
|
@ -11,6 +11,7 @@
|
||||
|
||||
// vehicle options
|
||||
static const apo::vehicle_t vehicle = apo::VEHICLE_CAR;
|
||||
//static const apo::halMode_t halMode = apo::MODE_HIL_CNTL;
|
||||
static const apo::halMode_t halMode = apo::MODE_LIVE;
|
||||
static const apo::board_t board = apo::BOARD_ARDUPILOTMEGA_1280;
|
||||
static const uint8_t heartBeatTimeout = 3;
|
||||
|
@ -80,18 +80,17 @@ AP_Autopilot::AP_Autopilot(AP_Navigator * navigator, AP_Guide * guide,
|
||||
} else if (hal->getMode() == MODE_HIL_CNTL) { // hil
|
||||
hal->hil->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
|
||||
hal->hil->receive();
|
||||
Serial.println("HIL Receive Called");
|
||||
if (_navigator->getTimeStamp() != 0) {
|
||||
// give hil a chance to send some packets
|
||||
for (int i = 0; i < 5; i++) {
|
||||
hal->debug->println_P(PSTR("reading initial hil packets"));
|
||||
hal->gcs->sendText(SEVERITY_LOW,
|
||||
PSTR("reading initial hil packets"));
|
||||
hal->gcs->sendText(SEVERITY_LOW, PSTR("reading initial hil packets"));
|
||||
delay(1000);
|
||||
}
|
||||
break;
|
||||
}
|
||||
hal->debug->println_P(PSTR("waiting for hil packet"));
|
||||
hal->gcs->sendText(SEVERITY_LOW, PSTR("waiting for hil packets"));
|
||||
}
|
||||
delay(500);
|
||||
}
|
||||
|
@ -128,7 +128,7 @@ void MavlinkGuide::nextCommand() {
|
||||
_nextCommandCalls = 0;
|
||||
}
|
||||
|
||||
_cmdIndex = getNextIndex();
|
||||
setCurrentIndex(getNextIndex());
|
||||
//Serial.print("cmd : "); Serial.println(int(_cmdIndex));
|
||||
//Serial.print("cmd prev : "); Serial.println(int(getPreviousIndex()));
|
||||
//Serial.print("cmd num : "); Serial.println(int(getNumberOfCommands()));
|
||||
|
Loading…
Reference in New Issue
Block a user