Commit 199c6f93 authored by Don Gagne's avatar Don Gagne

Delay HOME_POSITION to better simulate reality

parent af824e20
......@@ -88,6 +88,7 @@ MockLink::MockLink(MockConfiguration* config)
, _fileServer(NULL)
, _sendStatusText(false)
, _apmSendHomePositionOnEmptyList(false)
, _sendHomePositionDelayCount(2)
{
_config = config;
if (_config) {
......@@ -171,7 +172,12 @@ void MockLink::_run1HzTasks(void)
{
if (_mavlinkStarted && _connected) {
_sendHeartBeat();
if (_sendHomePositionDelayCount > 0) {
// We delay home position a bit to be more realistic
_sendHomePositionDelayCount--;
} else {
_sendHomePosition();
}
if (_sendStatusText) {
_sendStatusText = false;
_sendStatusTextMessages();
......@@ -715,6 +721,10 @@ void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode
void MockLink::_sendHomePosition(void)
{
// APM stack does not yet support HOME_POSITION
if (_firmwareType != MAV_AUTOPILOT_ARDUPILOTMEGA) {
mavlink_message_t msg;
float bogus[4];
......@@ -733,6 +743,7 @@ void MockLink::_sendHomePosition(void)
&bogus[0],
0.0f, 0.0f, 0.0f);
respondWithMavlinkMessage(msg);
}
}
void MockLink::_sendGpsRawInt(void)
......
......@@ -191,6 +191,8 @@ private:
bool _sendStatusText;
bool _apmSendHomePositionOnEmptyList;
int _sendHomePositionDelayCount;
static float _vehicleLatitude;
static float _vehicleLongitude;
static float _vehicleAltitude;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment