mirror of https://github.com/ArduPilot/ardupilot
Heartbeat failsafe added for APO.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1940 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
7b7ba0df1f
commit
9b25875baf
|
@ -200,13 +200,13 @@ public:
|
|||
//airSpeedCommand = 0;
|
||||
//groundSpeedCommand = 0;
|
||||
headingCommand -= 45*deg2Rad;
|
||||
_hal->debug->print("Obstacle Distance (m): ");
|
||||
_hal->debug->println(frontDistance);
|
||||
_hal->debug->print("Obstacle avoidance Heading Command: ");
|
||||
_hal->debug->println(headingCommand);
|
||||
_hal->debug->printf_P(
|
||||
PSTR("Front Distance, %f\n"),
|
||||
frontDistance);
|
||||
// _hal->debug->print("Obstacle Distance (m): ");
|
||||
// _hal->debug->println(frontDistance);
|
||||
// _hal->debug->print("Obstacle avoidance Heading Command: ");
|
||||
// _hal->debug->println(headingCommand);
|
||||
// _hal->debug->printf_P(
|
||||
// PSTR("Front Distance, %f\n"),
|
||||
// frontDistance);
|
||||
}
|
||||
if (_rangeFinderBack && _rangeFinderBack->distance < 5) {
|
||||
airSpeedCommand = 0;
|
||||
|
|
|
@ -47,7 +47,7 @@ public:
|
|||
AP_HardwareAbstractionLayer(halMode_t mode, board_t board, vehicle_t vehicle) :
|
||||
_mode(mode), _board(board), _vehicle(vehicle), adc(),
|
||||
gps(), baro(), compass(), rangeFinders(),
|
||||
imu(), rc(), gcs(), hil(), debug(), load()
|
||||
imu(), rc(), gcs(), hil(), debug(), load(), lastHeartBeat()
|
||||
{
|
||||
}
|
||||
/**
|
||||
|
|
|
@ -131,6 +131,7 @@ public:
|
|||
_hal->rc[CH_RIGHT]->setPosition(0);
|
||||
_hal->rc[CH_FRONT]->setPosition(0);
|
||||
_hal->rc[CH_BACK]->setPosition(0);
|
||||
return;
|
||||
}
|
||||
|
||||
// read and set pwm so they can be read as positions later
|
||||
|
|
|
@ -60,7 +60,7 @@ const float loop4Rate = 0.1;
|
|||
|
||||
// max time in seconds to allow flight without ground station comms
|
||||
// zero will ignore timeout
|
||||
const uint8_t heartbeatTimeout = 3.0;
|
||||
const uint8_t heartbeatTimeout = 3;
|
||||
|
||||
//---------HARDWARE CONFIG ----------------//
|
||||
|
||||
|
|
|
@ -60,7 +60,7 @@ const float loop4Rate = 0.1;
|
|||
|
||||
// max time in seconds to allow flight without ground station comms
|
||||
// zero will ignore timeout
|
||||
const uint8_t heartbeatTimeout = 3.0;
|
||||
const uint8_t heartbeatTimeout = 3;
|
||||
|
||||
//---------HARDWARE CONFIG ----------------//
|
||||
|
||||
|
|
Loading…
Reference in New Issue