From db96b6c08d4567b94272b006b760080921c4c76f Mon Sep 17 00:00:00 2001 From: Mark Sauder Date: Fri, 28 Jun 2019 19:46:02 -0600 Subject: [PATCH] cm8jl65: Refactor driver, employ uniform initialization, format, and deprecate ringbuffer and IOCTL. (#11853) * Move cm8jl65 class member variable initialization from constructor list to declarations. Format whitespace and move method doxy comments to declarations. * Refactor the cm8jl65 driver start() method, and rename info()->status(). * Continued refactoring of the cm8jl65 driver class: - Condense all class files into a single *.cpp file and give class scope resolution to previously unscoped methods. - Refactor cm8jl65 namespace level driver entry methods to reduce code and improve clarity. - Breakout CDev specific initialization LOC into the device_init() method. - Move the endian modification inside of the crc16_calc() method. * Deprecate the hardware ringbuffer, _class_instance, and ioctl() from the cm8jl65 driver. --- .../distance_sensor/cm8jl65/CMakeLists.txt | 3 +- .../distance_sensor/cm8jl65/cm8jl65.cpp | 898 +++++++++--------- .../cm8jl65/cm8jl65_parser.cpp | 195 ---- .../distance_sensor/cm8jl65/cm8jl65_parser.h | 73 -- 4 files changed, 439 insertions(+), 730 deletions(-) delete mode 100644 src/drivers/distance_sensor/cm8jl65/cm8jl65_parser.cpp delete mode 100644 src/drivers/distance_sensor/cm8jl65/cm8jl65_parser.h diff --git a/src/drivers/distance_sensor/cm8jl65/CMakeLists.txt b/src/drivers/distance_sensor/cm8jl65/CMakeLists.txt index a4843c263b0f..3c4f667a71c0 100644 --- a/src/drivers/distance_sensor/cm8jl65/CMakeLists.txt +++ b/src/drivers/distance_sensor/cm8jl65/CMakeLists.txt @@ -33,10 +33,9 @@ px4_add_module( MODULE drivers__cm8jl65 MAIN cm8jl65 - STACK_MAIN 1400 + STACK_MAIN 1200 SRCS cm8jl65.cpp - cm8jl65_parser.cpp MODULE_CONFIG module.yaml ) diff --git a/src/drivers/distance_sensor/cm8jl65/cm8jl65.cpp b/src/drivers/distance_sensor/cm8jl65/cm8jl65.cpp index 9cd30c6e3380..01c21cdf1fa2 100644 --- a/src/drivers/distance_sensor/cm8jl65/cm8jl65.cpp +++ b/src/drivers/distance_sensor/cm8jl65/cm8jl65.cpp @@ -37,458 +37,509 @@ * * Driver for the Lanbao PSK-CM8JL65-CC5 distance sensor. * Make sure to disable MAVLINK messages (MAV_0_CONFIG PARAMETER) - * on the serial port you connect the sensor,i.e TELEM1. + * on the serial port you connect the sensor,i.e TELEM2. * */ +#include #include #include #include - -#include +#include #include +#include #include -#include #include -#include -#include -#include +#include #include +#include -#include - -#include -#include #include #include - +#include +#include +#include +#include +#include +#include #include #include -#include "cm8jl65_parser.h" +using namespace time_literals; /* Configuration Constants */ +#define CM8JL65_TAKE_RANGE_REG 'd' +#define CM8JL65_DEFAULT_PORT "/dev/ttyS2" // Default serial port on Pixhawk (TELEM2), baudrate 115200 +#define CM8JL65_MEASURE_INTERVAL 50_ms // 50ms default sensor conversion time. -#define CM8JL65_TAKE_RANGE_REG 'd' +/* Frame start delimiter */ +#define START_FRAME_DIGIT1 0xA5 +#define START_FRAME_DIGIT2 0x5A -// designated serial port on Pixhawk (TELEM2) -#define CM8JL65_DEFAULT_PORT "/dev/ttyS2" // Its baudrate is 115200 +/** + * Frame format definition + * 1B 1B 1B 1B 2B + * | 0xA5 | 0x5A | distance-MSB | distance-LSB | crc-16 | + * + * Frame data saved for CRC calculation + */ +#define DISTANCE_MSB_POS 2 +#define DISTANCE_LSB_POS 3 +#define PARSER_BUF_LENGTH 4 + +static const unsigned char crc_msb_vector[] = { + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, + 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, + 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40 +}; -// normal conversion wait time -#define CM8JL65_CONVERSION_INTERVAL 50*1000UL/* 50ms */ +static const unsigned char crc_lsb_vector[] = { + 0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, 0x07, 0xC7, + 0x05, 0xC5, 0xC4, 0x04, 0xCC, 0x0C, 0x0D, 0xCD, 0x0F, 0xCF, 0xCE, 0x0E, + 0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 0x09, 0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9, + 0x1B, 0xDB, 0xDA, 0x1A, 0x1E, 0xDE, 0xDF, 0x1F, 0xDD, 0x1D, 0x1C, 0xDC, + 0x14, 0xD4, 0xD5, 0x15, 0xD7, 0x17, 0x16, 0xD6, 0xD2, 0x12, 0x13, 0xD3, + 0x11, 0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3, 0xF2, 0x32, + 0x36, 0xF6, 0xF7, 0x37, 0xF5, 0x35, 0x34, 0xF4, 0x3C, 0xFC, 0xFD, 0x3D, + 0xFF, 0x3F, 0x3E, 0xFE, 0xFA, 0x3A, 0x3B, 0xFB, 0x39, 0xF9, 0xF8, 0x38, + 0x28, 0xE8, 0xE9, 0x29, 0xEB, 0x2B, 0x2A, 0xEA, 0xEE, 0x2E, 0x2F, 0xEF, + 0x2D, 0xED, 0xEC, 0x2C, 0xE4, 0x24, 0x25, 0xE5, 0x27, 0xE7, 0xE6, 0x26, + 0x22, 0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60, 0x61, 0xA1, + 0x63, 0xA3, 0xA2, 0x62, 0x66, 0xA6, 0xA7, 0x67, 0xA5, 0x65, 0x64, 0xA4, + 0x6C, 0xAC, 0xAD, 0x6D, 0xAF, 0x6F, 0x6E, 0xAE, 0xAA, 0x6A, 0x6B, 0xAB, + 0x69, 0xA9, 0xA8, 0x68, 0x78, 0xB8, 0xB9, 0x79, 0xBB, 0x7B, 0x7A, 0xBA, + 0xBE, 0x7E, 0x7F, 0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 0xB5, + 0x77, 0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3, 0x73, 0xB1, 0x71, 0x70, 0xB0, + 0x50, 0x90, 0x91, 0x51, 0x93, 0x53, 0x52, 0x92, 0x96, 0x56, 0x57, 0x97, + 0x55, 0x95, 0x94, 0x54, 0x9C, 0x5C, 0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E, + 0x5A, 0x9A, 0x9B, 0x5B, 0x99, 0x59, 0x58, 0x98, 0x88, 0x48, 0x49, 0x89, + 0x4B, 0x8B, 0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 0x8C, + 0x44, 0x84, 0x85, 0x45, 0x87, 0x47, 0x46, 0x86, 0x82, 0x42, 0x43, 0x83, + 0x41, 0x81, 0x80, 0x40 +}; class CM8JL65 : public cdev::CDev, public px4::ScheduledWorkItem { public: - - // Constructor + /** + * Default Constructor + * @param port The serial port to open for communicating with the sensor. + * @param rotation The sensor rotation relative to the vehicle body. + */ CM8JL65(const char *port = CM8JL65_DEFAULT_PORT, uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING); - // Virtual destructor + /** Virtual destructor */ virtual ~CM8JL65() override; + /** + * Method : init() + * This method initializes the general driver for a range finder sensor. + */ virtual int init() override; - virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg) override; /** - * Diagnostics - print some basic information about the driver. - */ - void print_info(); + * Diagnostics - print some basic information about the driver. + */ + void print_info(); private: - char _port[20]; - uint8_t _rotation; - float _min_distance; - float _max_distance; - int _conversion_interval; - ringbuffer::RingBuffer *_reports; - int _fd; - uint8_t _linebuf[25]; - uint8_t _cycle_counter; - - enum CM8JL65_PARSE_STATE _parse_state; - unsigned char _frame_data[PARSER_BUF_LENGTH]; - uint16_t _crc16; - int _distance_mm; + enum CM8JL65_PARSE_STATE { + WAITING_FRAME = 0, + DIGIT_1, + DIGIT_2, + MSB_DATA, + LSB_DATA, + CHECKSUM + }; - int _class_instance; - int _orb_class_instance; + /** + * Calculates the 16 byte crc value for the data frame. + * @param data_frame The data frame to compute a checksum for. + * @param crc16_length The length of the data frame. + */ + uint16_t crc16_calc(const unsigned char *data_frame, uint8_t crc16_length); - orb_advert_t _distance_sensor_topic; + /** + * Reads data from serial UART and places it into a buffer. + */ + int collect(); - perf_counter_t _sample_perf; - perf_counter_t _comms_errors; + int data_parser(const uint8_t check_byte, uint8_t parserbuf[PARSER_BUF_LENGTH], CM8JL65_PARSE_STATE &state, + uint16_t &crc16, int &distance); /** - * Initialise the automatic measurement state machine and start it. - * - * @note This function is called at open and error time. It might make sense - * to make it more aggressive about resetting the bus in case of errors. - */ - void start(); + * Opens and configures the UART serial communications port. + * @param speed The baudrate (speed) to configure the serial UART port. + */ + int open_serial_port(const speed_t speed = B115200); /** - * Stop the automatic measurement state machine. - */ - void stop(); + * Perform a reading cycle; collect from the previous measurement + * and start a new one. + */ + void Run() override; /** - * Set the min and max distance thresholds. - */ - void set_minimum_distance(float min); - void set_maximum_distance(float max); - float get_minimum_distance(); - float get_maximum_distance(); + * Initialise the automatic measurement state machine and start it. + * @note This function is called at open and error time. It might make sense + * to make it more aggressive about resetting the bus in case of errors. + */ + void start(); /** - * Perform a reading cycle; collect from the previous measurement - * and start a new one. - */ - void Run() override; + * Stops the automatic measurement state machine. + */ + void stop(); - int collect(); + char _port[20] {}; -}; + unsigned char _frame_data[PARSER_BUF_LENGTH] {START_FRAME_DIGIT1, START_FRAME_DIGIT2, 0, 0}; -/* - * Driver 'main' command. - */ -extern "C" __EXPORT int cm8jl65_main(int argc, char *argv[]); + int _measure_interval{CM8JL65_MEASURE_INTERVAL}; + int _file_descriptor{-1}; + int _orb_class_instance{-1}; + + uint8_t _cycle_counter{0}; + uint8_t _linebuf[25] {}; + uint8_t _rotation{0}; + + uint16_t _crc16{0}; + + float _max_distance{9.0f}; + float _min_distance{0.10f}; + + CM8JL65_PARSE_STATE _parse_state{WAITING_FRAME}; + + orb_advert_t _distance_sensor_topic{nullptr}; + + perf_counter_t _comms_errors{perf_alloc(PC_COUNT, "cm8jl65_com_err")}; + perf_counter_t _sample_perf{perf_alloc(PC_ELAPSED, "cm8jl65_read")}; +}; -/** -* Method : Constructor -* -* @note This method initializes the class variables -*/ CM8JL65::CM8JL65(const char *port, uint8_t rotation) : - CDev(RANGE_FINDER0_DEVICE_PATH), + CDev(RANGE_FINDER_BASE_DEVICE_PATH), ScheduledWorkItem(px4::wq_configurations::hp_default), - _rotation(rotation), - _min_distance(0.10f), - _max_distance(9.0f), - _conversion_interval(CM8JL65_CONVERSION_INTERVAL), - _reports(nullptr), - _fd(-1), - _cycle_counter(0), - _parse_state(STATE0_WAITING_FRAME), - _frame_data{START_FRAME_DIGIT1, START_FRAME_DIGIT2, 0, 0}, - _crc16(0), - _distance_mm(-1), - _class_instance(-1), - _orb_class_instance(-1), - _distance_sensor_topic(nullptr), - _sample_perf(perf_alloc(PC_ELAPSED, "cm8jl65_read")), - _comms_errors(perf_alloc(PC_COUNT, "cm8jl65_com_err")) + _rotation(rotation) { - /* store port name */ + // Store the port name. strncpy(_port, port, sizeof(_port) - 1); - /* enforce null termination */ + // Enforce null termination. _port[sizeof(_port) - 1] = '\0'; } -// Destructor CM8JL65::~CM8JL65() { - /* make sure we are truly inactive */ + // Ensure we are truly inactive. stop(); - /* free any existing reports */ - if (_reports != nullptr) { - delete _reports; - } - - if (_class_instance != -1) { - unregister_class_devname(RANGE_FINDER_BASE_DEVICE_PATH, _class_instance); - } - perf_free(_sample_perf); perf_free(_comms_errors); } -/** -* Method : init() -* -* This method setup the general driver for a range finder sensor. -*/ +uint16_t +CM8JL65::crc16_calc(const unsigned char *data_frame, uint8_t crc16_length) +{ + // compute CRC16 IBM 8005 + unsigned char crc_high_byte = 0xFF; + unsigned char crc_low_byte = 0xFF; + size_t index = 0; + + while (crc16_length--) { + index = crc_low_byte ^ *(data_frame++); + crc_low_byte = (unsigned char)(crc_high_byte ^ crc_msb_vector[index]); + crc_high_byte = crc_lsb_vector[index]; + } + + uint16_t crc16 = (crc_high_byte << 8 | crc_low_byte); + crc16 = (crc16 >> 8) | (crc16 << 8); // Convert endian + + return crc16; +} int -CM8JL65::init() +CM8JL65::collect() { - /* status */ - int ret = 0; + perf_begin(_sample_perf); - do { /* create a scope to handle exit conditions using break */ + int bytes_processed = 0; + int distance_mm = -1; + int index = 0; - /* do regular cdev init */ - ret = CDev::init(); + bool crc_valid = false; - if (ret != OK) { break; } + // Read from the sensor UART buffer. + int bytes_read = ::read(_file_descriptor, &_linebuf[0], sizeof(_linebuf)); - /* allocate basic report buffers */ - _reports = new ringbuffer::RingBuffer(2, sizeof(distance_sensor_s)); + if (bytes_read > 0) { + index = bytes_read - 6 ; - if (_reports == nullptr) { - PX4_ERR("alloc failed"); - ret = -1; - break; - } + while (index >= 0 && !crc_valid) { + if (_linebuf[index] == START_FRAME_DIGIT1) { + bytes_processed = index; - _class_instance = register_class_devname(RANGE_FINDER_BASE_DEVICE_PATH); + while (bytes_processed < bytes_read && !crc_valid) { + if (data_parser(_linebuf[bytes_processed], _frame_data, _parse_state, _crc16, distance_mm) == PX4_OK) { + crc_valid = true; + } - /* get a publish handle on the range finder topic */ - struct distance_sensor_s ds_report = {}; + bytes_processed++; + } - _distance_sensor_topic = orb_advertise_multi(ORB_ID(distance_sensor), &ds_report, - &_orb_class_instance, ORB_PRIO_HIGH); + _parse_state = WAITING_FRAME; + } - if (_distance_sensor_topic == nullptr) { - PX4_ERR("failed to create distance_sensor object"); + index--; } - } while (0); + } else { + PX4_INFO("read error: %d", bytes_read); + perf_count(_comms_errors); + perf_end(_sample_perf); + return PX4_ERROR; + } - return ret; -} + if (!crc_valid) { + return -EAGAIN; + } -void -CM8JL65::set_minimum_distance(float min) -{ - _min_distance = min; -} + bytes_read = OK; -void -CM8JL65::set_maximum_distance(float max) -{ - _max_distance = max; -} + distance_sensor_s report; + report.current_distance = static_cast(distance_mm) / 1000.0f; + report.id = 0; // TODO: set proper ID. + report.max_distance = _max_distance; + report.min_distance = _min_distance; + report.orientation = _rotation; + report.signal_quality = -1; + report.timestamp = hrt_absolute_time(); + report.type = distance_sensor_s::MAV_DISTANCE_SENSOR_LASER; + report.variance = 0.0f; + + // Publish the new report. + orb_publish(ORB_ID(distance_sensor), _distance_sensor_topic, &report); -float -CM8JL65::get_minimum_distance() -{ - return _min_distance; -} + // Notify anyone waiting for data. + poll_notify(POLLIN); + perf_end(_sample_perf); -float -CM8JL65::get_maximum_distance() -{ - return _max_distance; + return PX4_OK; } int -CM8JL65::ioctl(device::file_t *filp, int cmd, unsigned long arg) +CM8JL65::data_parser(const uint8_t check_byte, uint8_t parserbuf[PARSER_BUF_LENGTH], + CM8JL65_PARSE_STATE &state, uint16_t &crc16, int &distance) { - switch (cmd) { - - case SENSORIOCSPOLLRATE: { - switch (arg) { - - /* zero would be bad */ - case 0: - return -EINVAL; - - /* set default polling rate */ - case SENSOR_POLLRATE_DEFAULT: { - start(); - return OK; - } - - /* adjust to a legal polling interval in Hz */ - default: { - - /* convert hz to tick interval via microseconds */ - int interval = (1000000 / arg); + switch (state) { + case WAITING_FRAME: + if (check_byte == START_FRAME_DIGIT1) { + state = DIGIT_1; + } - /* check against maximum rate */ - if (interval < _conversion_interval) { - return -EINVAL; - } + break; - start(); + case DIGIT_1: + if (check_byte == START_FRAME_DIGIT1) { + state = DIGIT_1; + } else if (check_byte == START_FRAME_DIGIT2) { + state = DIGIT_2; - return OK; - } - } + } else { + state = WAITING_FRAME; } - default: - /* give it to the superclass */ - return CDev::ioctl(filp, cmd, arg); - } -} + break; -int - -/* - * Method: collect() - * - * This method reads data from serial UART and places it into a buffer -*/ -CM8JL65::collect() -{ - int bytes_read = 0; - int bytes_processed = 0; - int i = 0; - bool crc_valid = false; + case DIGIT_2: + state = MSB_DATA; + parserbuf[DISTANCE_MSB_POS] = check_byte; // MSB Data + break; + case MSB_DATA: + state = LSB_DATA; + parserbuf[DISTANCE_LSB_POS] = check_byte; // LSB Data - perf_begin(_sample_perf); + // Calculate CRC. + crc16 = crc16_calc(parserbuf, PARSER_BUF_LENGTH); + break; + case LSB_DATA: + if (check_byte == (crc16 >> 8)) { + state = CHECKSUM; - /* read from the sensor (uart buffer) */ - bytes_read = ::read(_fd, &_linebuf[0], sizeof(_linebuf)); + } else { + state = WAITING_FRAME; + } - if (bytes_read < 0) { - PX4_DEBUG("read err: %d \n", bytes_read); - perf_count(_comms_errors); - perf_end(_sample_perf); + break; - } else if (bytes_read > 0) { - // printf("Bytes read: %d \n",bytes_read); - i = bytes_read - 6 ; + case CHECKSUM: + // Here, reset state to `NOT-STARTED` no matter crc ok or not + state = WAITING_FRAME; - while ((i >= 0) && (!crc_valid)) { - if (_linebuf[i] == START_FRAME_DIGIT1) { - bytes_processed = i; + if (check_byte == (crc16 & 0xFF)) { + // printf("Checksum verified \n"); + distance = (parserbuf[DISTANCE_MSB_POS] << 8) | parserbuf[DISTANCE_LSB_POS]; + return PX4_OK; + } - while ((bytes_processed < bytes_read) && (!crc_valid)) { - // printf("In the cycle, processing byte %d, 0x%02X \n",bytes_processed, _linebuf[bytes_processed]); - if (OK == cm8jl65_parser(_linebuf[bytes_processed], _frame_data, _parse_state, _crc16, _distance_mm)) { - crc_valid = true; - } + break; - bytes_processed++; - } + default: + // Nothing todo + break; + } - _parse_state = STATE0_WAITING_FRAME; + return PX4_ERROR; +} - } +int +CM8JL65::init() +{ + // Intitialize the character device. + if (CDev::init() != OK) { + return PX4_ERROR; + } - i--; - } + // Get a publish handle on the range finder topic. + distance_sensor_s ds_report = {}; + _distance_sensor_topic = orb_advertise_multi(ORB_ID(distance_sensor), &ds_report, + &_orb_class_instance, ORB_PRIO_HIGH); + if (_distance_sensor_topic == nullptr) { + PX4_ERR("failed to create distance_sensor object"); } - if (!crc_valid) { - return -EAGAIN; + start(); + return PX4_OK; +} + +int +CM8JL65::open_serial_port(const speed_t speed) +{ + // File descriptor initialized? + if (_file_descriptor > 0) { + // PX4_INFO("serial port already open"); + return PX4_OK; } + // Configure port flags for read/write, non-controlling, non-blocking. + int flags = (O_RDWR | O_NOCTTY | O_NONBLOCK); - //printf("val (int): %d, raw: 0x%08X, valid: %s \n", _distance_mm, _frame_data, ((crc_valid) ? "OK" : "NO")); + // Open the serial port. + _file_descriptor = ::open(_port, flags); - struct distance_sensor_s report; + if (_file_descriptor < 0) { + PX4_ERR("open failed (%i)", errno); + return PX4_ERROR; + } - report.timestamp = hrt_absolute_time(); - report.type = distance_sensor_s::MAV_DISTANCE_SENSOR_LASER; - report.orientation = _rotation; - report.current_distance = _distance_mm / 1000.0f; - report.min_distance = get_minimum_distance(); - report.max_distance = get_maximum_distance(); - report.variance = 0.0f; - report.signal_quality = -1; - /* TODO: set proper ID */ - report.id = 0; + termios uart_config = {}; - /* publish it */ - orb_publish(ORB_ID(distance_sensor), _distance_sensor_topic, &report); + // Store the current port configuration. attributes. + tcgetattr(_file_descriptor, &uart_config); - _reports->force(&report); + // Clear ONLCR flag (which appends a CR for every LF). + uart_config.c_oflag &= ~ONLCR; - /* notify anyone waiting for data */ - poll_notify(POLLIN); + // No parity, one stop bit. + uart_config.c_cflag &= ~(CSTOPB | PARENB); - bytes_read = OK; + // Set the input baud rate in the uart_config struct. + int termios_state = cfsetispeed(&uart_config, speed); - perf_end(_sample_perf); + if (termios_state < 0) { + PX4_ERR("CFG: %d ISPD", termios_state); + ::close(_file_descriptor); + return PX4_ERROR; + } - return OK; + // Set the output baud rate in the uart_config struct. + termios_state = cfsetospeed(&uart_config, speed); -} + if (termios_state < 0) { + PX4_ERR("CFG: %d OSPD", termios_state); + ::close(_file_descriptor); + return PX4_ERROR; + } -void -CM8JL65::start() -{ - PX4_INFO("driver started"); + // Apply the modified port attributes. + termios_state = tcsetattr(_file_descriptor, TCSANOW, &uart_config); - _reports->flush(); + if (termios_state < 0) { + PX4_ERR("baud %d ATTR", termios_state); + ::close(_file_descriptor); + return PX4_ERROR; + } - /* schedule a cycle to start things */ - ScheduleNow(); + PX4_INFO("successfully opened UART port %s", _port); + return PX4_OK; } void -CM8JL65::stop() +CM8JL65::print_info() { - ScheduleClear(); + perf_print_counter(_sample_perf); + perf_print_counter(_comms_errors); } void CM8JL65::Run() { - /* fds initialized? */ - if (_fd < 0) { - /* open fd */ - _fd = ::open(_port, O_RDWR | O_NOCTTY | O_NONBLOCK); - - if (_fd < 0) { - PX4_ERR("open failed (%i)", errno); - return; - } - - struct termios uart_config; - - int termios_state; - - /* fill the struct for the new configuration */ - tcgetattr(_fd, &uart_config); - - /* clear ONLCR flag (which appends a CR for every LF) */ - uart_config.c_oflag &= ~ONLCR; - - /* no parity, one stop bit */ - uart_config.c_cflag &= ~(CSTOPB | PARENB); - - unsigned speed = B115200; - - /* set baud rate */ - if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) { - PX4_ERR("CFG: %d ISPD", termios_state); - } - - if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) { - PX4_ERR("CFG: %d OSPD", termios_state); - } - - if ((termios_state = tcsetattr(_fd, TCSANOW, &uart_config)) < 0) { - PX4_ERR("baud %d ATTR", termios_state); - } - } - - /* perform collection */ - int collect_ret = collect(); + // Ensure the serial port is open. + open_serial_port(); - if (collect_ret == -EAGAIN) { + // Perform collection. + if (collect() == -EAGAIN) { _cycle_counter++; } - /* schedule a fresh cycle call when a complete packet has been received */ - ScheduleDelayed(_conversion_interval); _cycle_counter = 0; } void -CM8JL65::print_info() +CM8JL65::start() { - perf_print_counter(_sample_perf); - perf_print_counter(_comms_errors); - _reports->print_info("report queue"); + // Schedule the driver at regular intervals. + ScheduleOnInterval(CM8JL65_MEASURE_INTERVAL, 0); + PX4_INFO("driver started"); } +void +CM8JL65::stop() +{ + // Ensure the serial port is closed. + ::close(_file_descriptor); + + // Clear the work queue schedule. + ScheduleClear(); +} + + /** * Local functions in support of the shell command. */ @@ -497,61 +548,71 @@ namespace cm8jl65 CM8JL65 *g_dev; -int start(const char *port, uint8_t rotation); -int stop(); -int test(); -int reset(); -int info(); +int reset(const char *port = CM8JL65_DEFAULT_PORT); +int start(const char *port = CM8JL65_DEFAULT_PORT, + const uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING); +int status(); +int stop(); +int test(const char *port = CM8JL65_DEFAULT_PORT); +int usage(); /** - * Start the driver. + * Reset the driver. */ int -start(const char *port, uint8_t rotation) +reset(const char *port) { - int fd; + if (stop() == PX4_OK) { + return start(port); + } + + return PX4_ERROR; +} +/** + * Start the driver. + */ +int +start(const char *port, const uint8_t rotation) +{ if (g_dev != nullptr) { - PX4_WARN("already started"); - return -1; + PX4_INFO("already started"); + return PX4_OK; } - /* create the driver */ + // Instantiate the driver. g_dev = new CM8JL65(port, rotation); if (g_dev == nullptr) { - goto fail; + PX4_ERR("object instantiate failed"); + return PX4_ERROR; } - if (OK != g_dev->init()) { - goto fail; + if (g_dev->init() != PX4_OK) { + PX4_ERR("driver start failed"); + delete g_dev; + g_dev = nullptr; + return PX4_ERROR; } - /* set the poll rate to default, starts automatic data collection */ - fd = open(RANGE_FINDER0_DEVICE_PATH, 0); - - if (fd < 0) { - PX4_ERR("device open fail (%i)", errno); - goto fail; - } + return PX4_OK; +} - if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { - PX4_ERR("failed to set baudrate %d", B115200); - goto fail; +/** + * Print the driver status. + */ +int +status() +{ + if (g_dev == nullptr) { + PX4_ERR("driver not running"); + return PX4_ERROR; } - PX4_DEBUG("cm8jl65::start() succeeded"); - return 0; - -fail: - PX4_DEBUG("cm8jl65::start() failed"); - - if (g_dev != nullptr) { - delete g_dev; - g_dev = nullptr; - } + printf("state @ %p\n", g_dev); + g_dev->print_info(); - return -1; + return PX4_OK; } /** @@ -562,12 +623,9 @@ int stop() if (g_dev != nullptr) { delete g_dev; g_dev = nullptr; - - } else { - return -1; } - return 0; + return PX4_ERROR; } /** @@ -576,115 +634,47 @@ int stop() * and automatic modes. */ int -test() +test(const char *port) { - struct distance_sensor_s report; - ssize_t sz; - - int fd = open(RANGE_FINDER0_DEVICE_PATH, O_RDONLY); + int fd = open(port, O_RDONLY); if (fd < 0) { - PX4_ERR("%s open failed (try 'cm8jl65 start' if the driver is not running", RANGE_FINDER0_DEVICE_PATH); - return -1; + PX4_ERR("%s open failed (try 'cm8jl65 start' if the driver is not running", port); + return PX4_ERROR; } - /* do a simple demand read */ - sz = read(fd, &report, sizeof(report)); + // Perform a simple demand read. + distance_sensor_s report; + ssize_t bytes_read = read(fd, &report, sizeof(report)); - if (sz != sizeof(report)) { + if (bytes_read != sizeof(report)) { PX4_ERR("immediate read failed"); - return -1; + return PX4_ERROR; } print_message(report); - - /* start the sensor polling at 2 Hz rate */ - if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) { - PX4_ERR("failed to set 2Hz poll rate"); - return -1; - } - - /* read the sensor 5x and report each value */ - for (unsigned i = 0; i < 5; i++) { - struct pollfd fds; - - /* wait for data to be ready */ - fds.fd = fd; - fds.events = POLLIN; - int ret = poll(&fds, 1, 2000); - - if (ret != 1) { - PX4_ERR("timed out"); - break; - } - - /* now go get it */ - sz = read(fd, &report, sizeof(report)); - - if (sz != sizeof(report)) { - PX4_ERR("read failed: got %zi vs exp. %zu", sz, sizeof(report)); - break; - } - - print_message(report); - } - - /* reset the sensor polling to the default rate */ - if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) { - PX4_ERR("ioctl SENSORIOCSPOLLRATE failed"); - return -1; - } - - return 0; + return PX4_OK; } -/** - * Reset the driver. - */ int -reset() +usage() { - int fd = open(RANGE_FINDER0_DEVICE_PATH, O_RDONLY); - - if (fd < 0) { - PX4_ERR("open failed (%i)", errno); - return -1; - } + PX4_INFO("usage: cm8jl65 command [options]"); + PX4_INFO("command:"); + PX4_INFO("\treset|start|status|stop|test"); + PX4_INFO("options:"); + PX4_INFO("\t-R --rotation (%d)", distance_sensor_s::ROTATION_DOWNWARD_FACING); + PX4_INFO("\t-d --device_path"); + return PX4_OK; +} - if (ioctl(fd, SENSORIOCRESET, 0) < 0) { - PX4_ERR("driver reset failed"); - return -1; - } +} // namespace cm8jl65 - if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { - PX4_ERR("driver poll restart failed"); - return -1; - } - - return 0; -} /** - * Print a little info about the driver. + * Driver 'main' command. */ -int -info() -{ - if (g_dev == nullptr) { - PX4_ERR("driver not running"); - return -1; - } - - printf("state @ %p\n", g_dev); - g_dev->print_info(); - - return 0; -} - -} // namespace - -int -cm8jl65_main(int argc, char *argv[]) +extern "C" __EXPORT int cm8jl65_main(int argc, char *argv[]) { uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING; const char *device_path = CM8JL65_DEFAULT_PORT; @@ -704,50 +694,38 @@ cm8jl65_main(int argc, char *argv[]) default: PX4_WARN("Unknown option!"); - return -1; + return cm8jl65::usage(); } } if (myoptind >= argc) { - goto out_error; + return cm8jl65::usage(); } - /* - * Start/load the driver. - */ + // Reset the driver. + if (!strcmp(argv[myoptind], "reset")) { + return cm8jl65::reset(device_path); + } + + // Start/load the driver. if (!strcmp(argv[myoptind], "start")) { return cm8jl65::start(device_path, rotation); } - /* - * Stop the driver - */ + // Print driver information. + if (!strcmp(argv[myoptind], "status")) { + return cm8jl65::status(); + } + + // Stop the driver if (!strcmp(argv[myoptind], "stop")) { return cm8jl65::stop(); } - /* - * Test the driver/device. - */ + // Test the driver/device. if (!strcmp(argv[myoptind], "test")) { return cm8jl65::test(); } - /* - * Reset the driver. - */ - if (!strcmp(argv[myoptind], "reset")) { - return cm8jl65::reset(); - } - - /* - * Print driver information. - */ - if (!strcmp(argv[myoptind], "info") || !strcmp(argv[myoptind], "status")) { - return cm8jl65::info(); - } - -out_error: - PX4_ERR("unrecognized command, try 'start', 'test', 'reset' or 'info'"); - return -1; + return cm8jl65::usage(); } diff --git a/src/drivers/distance_sensor/cm8jl65/cm8jl65_parser.cpp b/src/drivers/distance_sensor/cm8jl65/cm8jl65_parser.cpp deleted file mode 100644 index d7205210d7a6..000000000000 --- a/src/drivers/distance_sensor/cm8jl65/cm8jl65_parser.cpp +++ /dev/null @@ -1,195 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2018 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file cm8jl65_parser.cpp - * @author Claudio Micheli - * - */ - -#include "cm8jl65_parser.h" -#include -#include -#include - -#include "cm8jl65_parser.h" -#include -#include - - - - -static const unsigned char crc_msb_vector[] = { - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, - 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, - 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, - 0x00, 0xC1, 0x81, 0x40 -}; - -static const unsigned char crc_lsb_vector[] = { - 0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, 0x07, 0xC7, - 0x05, 0xC5, 0xC4, 0x04, 0xCC, 0x0C, 0x0D, 0xCD, 0x0F, 0xCF, 0xCE, 0x0E, - 0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 0x09, 0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9, - 0x1B, 0xDB, 0xDA, 0x1A, 0x1E, 0xDE, 0xDF, 0x1F, 0xDD, 0x1D, 0x1C, 0xDC, - 0x14, 0xD4, 0xD5, 0x15, 0xD7, 0x17, 0x16, 0xD6, 0xD2, 0x12, 0x13, 0xD3, - 0x11, 0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3, 0xF2, 0x32, - 0x36, 0xF6, 0xF7, 0x37, 0xF5, 0x35, 0x34, 0xF4, 0x3C, 0xFC, 0xFD, 0x3D, - 0xFF, 0x3F, 0x3E, 0xFE, 0xFA, 0x3A, 0x3B, 0xFB, 0x39, 0xF9, 0xF8, 0x38, - 0x28, 0xE8, 0xE9, 0x29, 0xEB, 0x2B, 0x2A, 0xEA, 0xEE, 0x2E, 0x2F, 0xEF, - 0x2D, 0xED, 0xEC, 0x2C, 0xE4, 0x24, 0x25, 0xE5, 0x27, 0xE7, 0xE6, 0x26, - 0x22, 0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60, 0x61, 0xA1, - 0x63, 0xA3, 0xA2, 0x62, 0x66, 0xA6, 0xA7, 0x67, 0xA5, 0x65, 0x64, 0xA4, - 0x6C, 0xAC, 0xAD, 0x6D, 0xAF, 0x6F, 0x6E, 0xAE, 0xAA, 0x6A, 0x6B, 0xAB, - 0x69, 0xA9, 0xA8, 0x68, 0x78, 0xB8, 0xB9, 0x79, 0xBB, 0x7B, 0x7A, 0xBA, - 0xBE, 0x7E, 0x7F, 0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 0xB5, - 0x77, 0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3, 0x73, 0xB1, 0x71, 0x70, 0xB0, - 0x50, 0x90, 0x91, 0x51, 0x93, 0x53, 0x52, 0x92, 0x96, 0x56, 0x57, 0x97, - 0x55, 0x95, 0x94, 0x54, 0x9C, 0x5C, 0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E, - 0x5A, 0x9A, 0x9B, 0x5B, 0x99, 0x59, 0x58, 0x98, 0x88, 0x48, 0x49, 0x89, - 0x4B, 0x8B, 0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 0x8C, - 0x44, 0x84, 0x85, 0x45, 0x87, 0x47, 0x46, 0x86, 0x82, 0x42, 0x43, 0x83, - 0x41, 0x81, 0x80, 0x40 -}; - - - - - -unsigned short crc16_calc(unsigned char *data_frame, uint8_t crc16_length) -{ - // compute CRC16 IBM 8005 - unsigned char crc_high_byte = 0xFF; - unsigned char crc_low_byte = 0xFF; - int i; - - while (crc16_length--) { - i = crc_low_byte ^ *(data_frame++); - crc_low_byte = (unsigned char)(crc_high_byte ^ crc_msb_vector[i]); - crc_high_byte = crc_lsb_vector[i]; - } - - return (unsigned short)(crc_high_byte << 8 | crc_low_byte); -} - -int cm8jl65_parser(uint8_t c, uint8_t parserbuf[PARSER_BUF_LENGTH], CM8JL65_PARSE_STATE &state, uint16_t &crc16, - int &dist) -{ - int ret = -1; - - switch (state) { - case STATE0_WAITING_FRAME: - if (c == START_FRAME_DIGIT1) { - state = STATE1_GOT_DIGIT1; - } - - break; - - case STATE1_GOT_DIGIT1: - if (c == START_FRAME_DIGIT2) { - state = STATE2_GOT_DIGIT2; - } - - else if (c == START_FRAME_DIGIT1) { - state = STATE1_GOT_DIGIT1; - - } else { - state = STATE0_WAITING_FRAME; - } - - break; - - case STATE2_GOT_DIGIT2: - state = STATE3_GOT_MSB_DATA; - parserbuf[DISTANCE_MSB_POS] = c; // MSB Data - break; - - case STATE3_GOT_MSB_DATA: - state = STATE4_GOT_LSB_DATA; - parserbuf[DISTANCE_LSB_POS] = c; // LSB Data - - // do crc calculation - crc16 = crc16_calc(parserbuf, PARSER_BUF_LENGTH); - // convert endian - crc16 = (crc16 >> 8) | (crc16 << 8); - break; - - - case STATE4_GOT_LSB_DATA: - if (c == (crc16 >> 8)) { - state = STATE5_GOT_CHKSUM1; - - } else { - // printf("Checksum invalid on high byte: 0x%02X, calculated: 0x%04X \n",c, *crc16); - state = STATE0_WAITING_FRAME; - - } - - break; - - case STATE5_GOT_CHKSUM1: - // Here, reset state to `NOT-STARTED` no matter crc ok or not - state = STATE0_WAITING_FRAME; - - if (c == (crc16 & 0xFF)) { - // printf("Checksum verified \n"); - dist = (parserbuf[DISTANCE_MSB_POS] << 8) | parserbuf[DISTANCE_LSB_POS]; - return 0; - } - - break; - - default: - // Nothing todo - break; - } - - return ret; -} diff --git a/src/drivers/distance_sensor/cm8jl65/cm8jl65_parser.h b/src/drivers/distance_sensor/cm8jl65/cm8jl65_parser.h deleted file mode 100644 index 979995e20609..000000000000 --- a/src/drivers/distance_sensor/cm8jl65/cm8jl65_parser.h +++ /dev/null @@ -1,73 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2018 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file cm8jl65.cpp - * @author Claudio Micheli - * - * Parser declarations for Lanbao PSK-CM8JL65-CC5 distance sensor - */ - -#pragma once - -#include -// frame start delimiter -#define START_FRAME_DIGIT1 0xA5 -#define START_FRAME_DIGIT2 0x5A - - -// Frame format definition -// -// 1B 1B 1B 1B 2B -// | 0xA5 | 0x5A | distance-MSB | distance-LSB | crc-16 | -// -// Frame data saved for CRC calculation -#define DISTANCE_MSB_POS 2 -#define DISTANCE_LSB_POS 3 -#define PARSER_BUF_LENGTH 4 - - -enum CM8JL65_PARSE_STATE { - STATE0_WAITING_FRAME = 0, - STATE1_GOT_DIGIT1, - STATE2_GOT_DIGIT2, - STATE3_GOT_MSB_DATA, - STATE4_GOT_LSB_DATA, - STATE5_GOT_CHKSUM1, - STATE6_GOT_CHKSUM2, -}; - - - -int cm8jl65_parser(uint8_t c, uint8_t parserbuf[PARSER_BUF_LENGTH], enum CM8JL65_PARSE_STATE &state, uint16_t &crc16, - int &dist);