ardupilot/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightL...

61 lines
2.1 KiB
C
Raw Normal View History

2013-12-02 07:02:56 -04:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef __AP_RANGEFINDER_PULSEDLIGHTLRF_H__
#define __AP_RANGEFINDER_PULSEDLIGHTLRF_H__
#include "RangeFinder.h"
#include "RangeFinder_Backend.h"
2013-12-02 07:02:56 -04:00
/* Connection diagram
*
* ------------------------------------------------------------------------------------
* | J2-1(LED) J2-2(5V) J2-3(Enable) J2-4(Ref Clk) J2-5(GND) J2-6(GND) |
2013-12-02 07:02:56 -04:00
* | |
* | |
* | J1-3(I2C Clk) J1-2(I2C Data) J1-1(GND) |
2013-12-02 07:02:56 -04:00
* ------------------------------------------------------------------------------------
*
* To connect to APM2.x:
* APM I2C Clock <-> J1-3
* APM I2C Data <-> J1-2
* APM GND (from output Rail) <-> J1-1 J2-5
* APM 5V (from output Rail fed by ESC or BEC) <-> J2-2
2013-12-02 07:02:56 -04:00
*
* APM2.x's I2C connector from outside edge: GND, Data, CLK, 3.3V
*/
// i2c address
#define AP_RANGEFINDER_PULSEDLIGHTLRF_ADDR 0x42
2013-12-02 07:02:56 -04:00
// min and max distances
#define AP_RANGEFINDER_PULSEDLIGHTLRF_MIN_DISTANCE 0
#define AP_RANGEFINDER_PULSEDLIGHTLRF_MAX_DISTANCE 1400
2013-12-02 07:02:56 -04:00
// registers
#define AP_RANGEFINDER_PULSEDLIGHTLRF_MEASURE_REG 0x00
#define AP_RANGEFINDER_PULSEDLIGHTLRF_DISTHIGH_REG 0x8f // high byte of distance measurement
2013-12-02 07:02:56 -04:00
// command register values
#define AP_RANGEFINDER_PULSEDLIGHTLRF_MSRREG_ACQUIRE 0x04 // Varies based on sensor revision, 0x04 is newest, 0x61 is older
2013-12-02 07:02:56 -04:00
class AP_RangeFinder_PulsedLightLRF : public AP_RangeFinder_Backend
2013-12-02 07:02:56 -04:00
{
public:
// constructor
AP_RangeFinder_PulsedLightLRF(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state);
2013-12-02 07:02:56 -04:00
// static detection function
static bool detect(RangeFinder &ranger, uint8_t instance);
2013-12-02 07:02:56 -04:00
// update state
void update(void);
2013-12-02 07:02:56 -04:00
private:
// start a reading
static bool start_reading(void);
static bool get_reading(uint16_t &reading_cm);
2013-12-02 07:02:56 -04:00
};
#endif // __AP_RANGEFINDER_PULSEDLIGHTLRF_H__