AP_RangeFinder: do not start the mavlink rangefinder as healthy

Also takes the opportunity to clean things up a little
This commit is contained in:
Peter Barker 2020-12-05 11:52:42 +11:00 committed by Peter Barker
parent c96ca2483e
commit 40eb9a8b99
2 changed files with 4 additions and 30 deletions

View File

@ -16,33 +16,6 @@
#include "AP_RangeFinder_MAVLink.h"
#include <AP_HAL/AP_HAL.h>
extern const AP_HAL::HAL& hal;
/*
The constructor also initialises the rangefinder. Note that this
constructor is not called until detect() returns true, so we
already know that we should setup the rangefinder
*/
AP_RangeFinder_MAVLink::AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
AP_RangeFinder_Backend(_state, _params)
{
state.last_reading_ms = AP_HAL::millis();
distance_cm = 0;
}
/*
detect if a MAVLink rangefinder is connected. We'll detect by
checking a parameter.
*/
bool AP_RangeFinder_MAVLink::detect()
{
// Assume that if the user set the RANGEFINDER_TYPE parameter to MAVLink,
// there is an attached MAVLink rangefinder
return true;
}
/*
Set the distance based on a MAVLINK message
*/

View File

@ -11,10 +11,11 @@ class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);
using AP_RangeFinder_Backend::AP_RangeFinder_Backend;
// static detection function
static bool detect();
// Assume that if the user set the RANGEFINDER_TYPE parameter to MAVLink,
// there is an attached MAVLink rangefinder
static bool detect() { return true; }
// update state
void update(void) override;