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
3
.gitignore
vendored
3
.gitignore
vendored
@ -16,4 +16,5 @@ build
|
|||||||
/Tools/ArdupilotMegaPlanner/bin/APM Planner.app
|
/Tools/ArdupilotMegaPlanner/bin/APM Planner.app
|
||||||
/Tools/ArdupilotMegaPlanner/obj
|
/Tools/ArdupilotMegaPlanner/obj
|
||||||
/Tools/ArdupilotMegaPlanner/resedit/bin
|
/Tools/ArdupilotMegaPlanner/resedit/bin
|
||||||
/Tools/ArdupilotMegaPlanner/resedit/obj
|
/Tools/ArdupilotMegaPlanner/resedit/obj
|
||||||
|
tags
|
||||||
|
@ -11,6 +11,7 @@
|
|||||||
|
|
||||||
// vehicle options
|
// vehicle options
|
||||||
static const apo::vehicle_t vehicle = apo::VEHICLE_CAR;
|
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::halMode_t halMode = apo::MODE_LIVE;
|
||||||
static const apo::board_t board = apo::BOARD_ARDUPILOTMEGA_1280;
|
static const apo::board_t board = apo::BOARD_ARDUPILOTMEGA_1280;
|
||||||
static const uint8_t heartBeatTimeout = 3;
|
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
|
} else if (hal->getMode() == MODE_HIL_CNTL) { // hil
|
||||||
hal->hil->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
|
hal->hil->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
|
||||||
hal->hil->receive();
|
hal->hil->receive();
|
||||||
Serial.println("HIL Receive Called");
|
|
||||||
if (_navigator->getTimeStamp() != 0) {
|
if (_navigator->getTimeStamp() != 0) {
|
||||||
// give hil a chance to send some packets
|
// give hil a chance to send some packets
|
||||||
for (int i = 0; i < 5; i++) {
|
for (int i = 0; i < 5; i++) {
|
||||||
hal->debug->println_P(PSTR("reading initial hil packets"));
|
hal->debug->println_P(PSTR("reading initial hil packets"));
|
||||||
hal->gcs->sendText(SEVERITY_LOW,
|
hal->gcs->sendText(SEVERITY_LOW, PSTR("reading initial hil packets"));
|
||||||
PSTR("reading initial hil packets"));
|
|
||||||
delay(1000);
|
delay(1000);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
hal->debug->println_P(PSTR("waiting for hil packet"));
|
hal->debug->println_P(PSTR("waiting for hil packet"));
|
||||||
|
hal->gcs->sendText(SEVERITY_LOW, PSTR("waiting for hil packets"));
|
||||||
}
|
}
|
||||||
delay(500);
|
delay(500);
|
||||||
}
|
}
|
||||||
|
@ -128,7 +128,7 @@ void MavlinkGuide::nextCommand() {
|
|||||||
_nextCommandCalls = 0;
|
_nextCommandCalls = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
_cmdIndex = getNextIndex();
|
setCurrentIndex(getNextIndex());
|
||||||
//Serial.print("cmd : "); Serial.println(int(_cmdIndex));
|
//Serial.print("cmd : "); Serial.println(int(_cmdIndex));
|
||||||
//Serial.print("cmd prev : "); Serial.println(int(getPreviousIndex()));
|
//Serial.print("cmd prev : "); Serial.println(int(getPreviousIndex()));
|
||||||
//Serial.print("cmd num : "); Serial.println(int(getNumberOfCommands()));
|
//Serial.print("cmd num : "); Serial.println(int(getNumberOfCommands()));
|
||||||
|
Loading…
Reference in New Issue
Block a user