AP_RangeFinder: move wasp to using common serial backend

This commit is contained in:
Peter Barker 2019-11-01 21:23:16 +11:00 committed by Peter Barker
parent 62f2f3e19e
commit 9829a1d08b
2 changed files with 13 additions and 24 deletions

View File

@ -13,9 +13,9 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#include "AP_RangeFinder_Wasp.h"
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_HAL/AP_HAL.h>
#include <ctype.h>
extern const AP_HAL::HAL& hal;
@ -69,24 +69,11 @@ const AP_Param::GroupInfo AP_RangeFinder_Wasp::var_info[] = {
AP_RangeFinder_Wasp::AP_RangeFinder_Wasp(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
uint8_t serial_instance) :
AP_RangeFinder_Backend(_state, _params) {
AP_RangeFinder_Backend_Serial(_state, _params, serial_instance)
{
AP_Param::setup_object_defaults(this, var_info);
const AP_SerialManager &serial_manager = AP::serialmanager();
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
if (uart != nullptr) {
uart->begin(115200);
// register Wasp specific parameters
state.var_info = var_info;
configuration_state = WASP_CFG_PROTOCOL;
}
}
// detection is considered as locating a serial port
bool AP_RangeFinder_Wasp::detect(uint8_t serial_instance) {
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
state.var_info = var_info;
}
// read - return last value measured by sensor

View File

@ -1,26 +1,29 @@
#pragma once
#include "RangeFinder.h"
#include "RangeFinder_Backend.h"
#include "RangeFinder_Backend_Serial.h"
// WASP 200 LRF
// http://www.attolloengineering.com/wasp-200-lrf.html
class AP_RangeFinder_Wasp : public AP_RangeFinder_Backend {
class AP_RangeFinder_Wasp : public AP_RangeFinder_Backend_Serial {
public:
AP_RangeFinder_Wasp(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
uint8_t serial_instance);
static bool detect(uint8_t serial_instance);
void update(void) override;
static const struct AP_Param::GroupInfo var_info[];
protected:
// Wasp is always 115200
uint32_t initial_baudrate(uint8_t serial_instance) const override {
return 115200;
}
virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
return MAV_DISTANCE_SENSOR_LASER;
}
@ -42,13 +45,12 @@ private:
WASP_CFG_DONE // done configuring
};
wasp_configuration_stage configuration_state;
wasp_configuration_stage configuration_state = WASP_CFG_PROTOCOL;
bool get_reading(uint16_t &reading_cm);
void parse_response(void);
AP_HAL::UARTDriver *uart;
char linebuf[10];
uint8_t linebuf_len;
AP_Int16 mavg;