Formatted code.

Signed-off-by: Claudio Micheli <claudio@auterion.com>
This commit is contained in:
Claudio Micheli 2019-01-04 12:12:56 +01:00 committed by Beat Küng
parent 7124cbf3af
commit ca0cd27c6b
3 changed files with 314 additions and 298 deletions

View File

@ -41,33 +41,33 @@
*
*/
#include <px4_config.h>
#include <px4_getopt.h>
#include <px4_workqueue.h>
#include <px4_config.h>
#include <px4_getopt.h>
#include <px4_workqueue.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <string.h>
#include <poll.h>
#include <stdio.h>
#include <unistd.h>
#include <termios.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <string.h>
#include <poll.h>
#include <stdio.h>
#include <unistd.h>
#include <termios.h>
#include <perf/perf_counter.h>
#include <perf/perf_counter.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_range_finder.h>
#include <drivers/device/device.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_range_finder.h>
#include <drivers/device/device.h>
#include <drivers/device/ringbuffer.h>
#include <uORB/uORB.h>
#include <uORB/topics/distance_sensor.h>
#include <uORB/uORB.h>
#include <uORB/topics/distance_sensor.h>
#include "cm8jl65_parser.h"
#include "cm8jl65_parser.h"
/* Configuration Constants */
/* Configuration Constants */
#ifndef CONFIG_SCHED_WORKQUEUE
# error This requires CONFIG_SCHED_WORKQUEUE.
@ -82,91 +82,91 @@
#define CM8JL65_CONVERSION_INTERVAL 50*1000UL/* 50ms */
class CM8JL65 : public cdev::CDev
{
public:
class CM8JL65 : public cdev::CDev
{
public:
// Constructor
CM8JL65(const char *port = CM8JL65_DEFAULT_PORT, uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING);
// Constructor
CM8JL65(const char *port = CM8JL65_DEFAULT_PORT, uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING);
// Virtual destructor
virtual ~CM8JL65();
// Virtual destructor
virtual ~CM8JL65();
virtual int init();
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
virtual int init();
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
*/
void print_info();
/**
* Diagnostics - print some basic information about the driver.
*/
void print_info();
private:
private:
char _port[20];
uint8_t _rotation;
float _min_distance;
float _max_distance;
int _conversion_interval;
work_s _work{};
ringbuffer::RingBuffer *_reports;
int _fd;
uint8_t _linebuf[25];
uint8_t _cycle_counter;
char _port[20];
uint8_t _rotation;
float _min_distance;
float _max_distance;
int _conversion_interval;
work_s _work{};
ringbuffer::RingBuffer *_reports;
int _fd;
uint8_t _linebuf[25];
uint8_t _cycle_counter;
enum CM8JL65_PARSE_STATE _parse_state;
unsigned char _frame_data[4];
uint16_t _crc16;
int _distance_mm;
enum CM8JL65_PARSE_STATE _parse_state;
unsigned char _frame_data[4];
uint16_t _crc16;
int _distance_mm;
int _class_instance;
int _orb_class_instance;
int _class_instance;
int _orb_class_instance;
orb_advert_t _distance_sensor_topic;
orb_advert_t _distance_sensor_topic;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
/**
/**
* 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();
void start();
/**
* Stop the automatic measurement state machine.
*/
void stop();
/**
* Stop the automatic measurement state machine.
*/
void stop();
/**
/**
* 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();
*/
void set_minimum_distance(float min);
void set_maximum_distance(float max);
float get_minimum_distance();
float get_maximum_distance();
/**
* Perform a reading cycle; collect from the previous measurement
* and start a new one.
*/
void cycle();
int collect();
/**
* Static trampoline from the workq context; because we don't have a
* generic workq wrapper yet.
*
* @param arg Instance pointer for the driver that is polling.
*/
static void cycle_trampoline(void *arg);
/**
* Perform a reading cycle; collect from the previous measurement
* and start a new one.
*/
void cycle();
int collect();
/**
* Static trampoline from the workq context; because we don't have a
* generic workq wrapper yet.
*
* @param arg Instance pointer for the driver that is polling.
*/
static void cycle_trampoline(void *arg);
};
};
/*
* Driver 'main' command.
*/
extern "C" __EXPORT int cm8jl65_main(int argc, char *argv[]);
/*
* Driver 'main' command.
*/
extern "C" __EXPORT int cm8jl65_main(int argc, char *argv[]);
/**
* Method : Constructor
@ -174,7 +174,7 @@
* @note This method initializes the class variables
*/
CM8JL65::CM8JL65(const char *port, uint8_t rotation) :
CM8JL65::CM8JL65(const char *port, uint8_t rotation) :
CDev(RANGE_FINDER0_DEVICE_PATH),
_rotation(rotation),
_min_distance(0.10f),
@ -182,17 +182,17 @@
_conversion_interval(CM8JL65_CONVERSION_INTERVAL),
_reports(nullptr),
_fd(-1),
_cycle_counter(0),
_cycle_counter(0),
_parse_state(STATE0_WAITING_FRAME),
_frame_data{START_FRAME_DIGIT1, START_FRAME_DIGIT2, 0, 0},
_crc16(0),
_distance_mm(-1),
_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"))
{
{
/* store port name */
strncpy(_port, port, sizeof(_port));
/* enforce null termination */
@ -228,39 +228,40 @@ CM8JL65::~CM8JL65()
int
CM8JL65::init()
{
/* status */
int ret = 0;
/* status */
int ret = 0;
do { /* create a scope to handle exit conditions using break */
do { /* create a scope to handle exit conditions using break */
/* do regular cdev init */
ret = CDev::init();
/* do regular cdev init */
ret = CDev::init();
if (ret != OK) { break; }
if (ret != OK) { break; }
/* allocate basic report buffers */
_reports = new ringbuffer::RingBuffer(2, sizeof(distance_sensor_s));
/* allocate basic report buffers */
_reports = new ringbuffer::RingBuffer(2, sizeof(distance_sensor_s));
if (_reports == nullptr) {
PX4_ERR("alloc failed");
ret = -1;
break;
}
_class_instance = register_class_devname(RANGE_FINDER_BASE_DEVICE_PATH);
if (_reports == nullptr) {
PX4_ERR("alloc failed");
ret = -1;
break;
}
/* get a publish handle on the range finder topic */
struct distance_sensor_s ds_report = {};
_class_instance = register_class_devname(RANGE_FINDER_BASE_DEVICE_PATH);
_distance_sensor_topic = orb_advertise_multi(ORB_ID(distance_sensor), &ds_report,
&_orb_class_instance, ORB_PRIO_HIGH);
/* get a publish handle on the range finder topic */
struct distance_sensor_s ds_report = {};
if (_distance_sensor_topic == nullptr) {
PX4_ERR("failed to create distance_sensor object");
}
_distance_sensor_topic = orb_advertise_multi(ORB_ID(distance_sensor), &ds_report,
&_orb_class_instance, ORB_PRIO_HIGH);
} while (0);
if (_distance_sensor_topic == nullptr) {
PX4_ERR("failed to create distance_sensor object");
}
return ret;
} while (0);
return ret;
}
void
@ -316,7 +317,7 @@ CM8JL65::ioctl(device::file_t *filp, int cmd, unsigned long arg)
return -EINVAL;
}
start();
start();
return OK;
@ -339,61 +340,64 @@ int
*/
CM8JL65::collect()
{
int bytes_read = 0;
int bytes_processed = 0;
int i = 0;
bool crc_valid = false;
int bytes_read = 0;
int bytes_processed = 0;
int i = 0;
bool crc_valid = false;
perf_begin(_sample_perf);
perf_begin(_sample_perf);
/* read from the sensor (uart buffer) */
bytes_read = ::read(_fd, &_linebuf[0], sizeof(_linebuf));
/* read from the sensor (uart buffer) */
bytes_read = ::read(_fd, &_linebuf[0], sizeof(_linebuf));
if (bytes_read < 0) {
PX4_DEBUG("read err: %d \n", bytes_read);
perf_count(_comms_errors);
perf_end(_sample_perf);
if (bytes_read < 0) {
PX4_DEBUG("read err: %d \n", bytes_read);
perf_count(_comms_errors);
perf_end(_sample_perf);
} else if (bytes_read > 0){
// printf("Bytes read: %d \n",bytes_read);
i = bytes_read - 6 ;
while ((i >=0) && (!crc_valid))
{
if (_linebuf[i] == START_FRAME_DIGIT1) {
bytes_processed = i;
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;
}
bytes_processed++;
}
_parse_state = STATE0_WAITING_FRAME;
} else if (bytes_read > 0) {
// printf("Bytes read: %d \n",bytes_read);
i = bytes_read - 6 ;
}
// else {printf("Starting frame wrong. Index: %d value 0x%02X \n",i,_linebuf[i]);}
i--;
}
while ((i >= 0) && (!crc_valid)) {
if (_linebuf[i] == START_FRAME_DIGIT1) {
bytes_processed = i;
}
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;
}
if (!crc_valid) {
bytes_processed++;
}
_parse_state = STATE0_WAITING_FRAME;
}
// else {printf("Starting frame wrong. Index: %d value 0x%02X \n",i,_linebuf[i]);}
i--;
}
}
if (!crc_valid) {
return -EAGAIN;
}
//printf("val (int): %d, raw: 0x%08X, valid: %s \n", _distance_mm, _frame_data, ((crc_valid) ? "OK" : "NO"));
//printf("val (int): %d, raw: 0x%08X, valid: %s \n", _distance_mm, _frame_data, ((crc_valid) ? "OK" : "NO"));
struct distance_sensor_s report;
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.current_distance = _distance_mm / 1000.0f;
report.min_distance = get_minimum_distance();
report.max_distance = get_maximum_distance();
report.covariance = 0.0f;
@ -413,19 +417,19 @@ CM8JL65::collect()
perf_end(_sample_perf);
/* ENABLE THIS IF YOU WANT TO PRINT OLD VALUES WHILE CRC CHECK IS WRONG
if (!crc_valid) {
return -EAGAIN;
}
else return OK; */
return OK;
/* ENABLE THIS IF YOU WANT TO PRINT OLD VALUES WHILE CRC CHECK IS WRONG
if (!crc_valid) {
return -EAGAIN;
}
else return OK; */
return OK;
}
void
CM8JL65::start()
{
PX4_INFO("driver started");
PX4_INFO("driver started");
_reports->flush();
@ -451,11 +455,11 @@ CM8JL65::cycle_trampoline(void *arg)
void
CM8JL65::cycle()
{
//PX4_DEBUG("CM8JL65::cycle() - in the cycle");
//PX4_DEBUG("CM8JL65::cycle() - in the cycle");
/* fds initialized? */
if (_fd < 0) {
/* open fd */
_fd = ::open(_port,O_RDWR);
_fd = ::open(_port, O_RDWR);
if (_fd < 0) {
PX4_ERR("open failed (%i)", errno);
@ -491,21 +495,21 @@ CM8JL65::cycle()
}
}
/* perform collection */
int collect_ret = collect();
/* perform collection */
int collect_ret = collect();
if (collect_ret == -EAGAIN) {
_cycle_counter++;
/* We are missing bytes to complete the packet, re-cycle at 1ms */
if (collect_ret == -EAGAIN) {
_cycle_counter++;
/* We are missing bytes to complete the packet, re-cycle at 1ms */
// work_queue(HPWORK,&_work,(worker_t)&CM8JL65::cycle_trampoline,this,USEC2TICK(1000LL));
// return;
}
}
/* schedule a fresh cycle call when a complete packet has been received */
//work_queue(HPWORK,&_work,(worker_t)&CM8JL65::cycle_trampoline,this,USEC2TICK(_conversion_interval - _cycle_counter * 1000LL));
work_queue(HPWORK,&_work,(worker_t)&CM8JL65::cycle_trampoline,this,USEC2TICK(_conversion_interval));
_cycle_counter = 0;
work_queue(HPWORK, &_work, (worker_t)&CM8JL65::cycle_trampoline, this, USEC2TICK(_conversion_interval));
_cycle_counter = 0;
}
void
@ -563,14 +567,16 @@ start(const char *port, uint8_t rotation)
}
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
PX4_ERR("failed to set baudrate %d", B115200);
PX4_ERR("failed to set baudrate %d", B115200);
goto fail;
}
PX4_DEBUG("cm8jl65::start() succeeded");
PX4_DEBUG("cm8jl65::start() succeeded");
return 0;
fail:
PX4_DEBUG("cm8jl65::start() failed");
PX4_DEBUG("cm8jl65::start() failed");
if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;

View File

@ -50,144 +50,154 @@
// Note : No clue what those static variables are
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
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
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 *dataFrame,uint8_t crc16_length) {
unsigned char crc_high_byte = 0xFF;
unsigned char crc_low_byte = 0xFF;
int i;
while (crc16_length--) {
i = crc_low_byte ^ *(dataFrame++);
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);
unsigned short crc16_calc(unsigned char *dataFrame, uint8_t crc16_length)
{
unsigned char crc_high_byte = 0xFF;
unsigned char crc_low_byte = 0xFF;
int i;
while (crc16_length--) {
i = crc_low_byte ^ *(dataFrame++);
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, CM8JL65_PARSE_STATE *state, uint16_t *crc16, int *dist)
{
int ret = -1;
int ret = -1;
// printf("parse byte 0x%02X \n", b);
switch (*state) {
case STATE0_WAITING_FRAME:
if (c == START_FRAME_DIGIT1) {
*state = STATE1_GOT_DIGIT1;
//printf("Got SFD1 \n");
}
break;
switch (*state) {
case STATE0_WAITING_FRAME:
if (c == START_FRAME_DIGIT1) {
*state = STATE1_GOT_DIGIT1;
//printf("Got SFD1 \n");
}
case STATE1_GOT_DIGIT1:
if (c == START_FRAME_DIGIT2) {
*state = STATE2_GOT_DIGIT2;
//printf("Got SFD2 \n");
}
// @NOTE: (claudio@auterion.com): if second byte is wrong we skip all the frame and restart parsing !!
else if (c == START_FRAME_DIGIT1) {
*state = STATE1_GOT_DIGIT1;
//printf("Discard previous SFD1, Got new SFD1 \n");
} else {
*state = STATE0_WAITING_FRAME;
}
break;
break;
case STATE2_GOT_DIGIT2:
*state = STATE3_GOT_MSB_DATA;
parserbuf[DISTANCE_MSB_POS] = c; // MSB Data
//printf("Got DATA1 0x%02X \n", c);
break;
case STATE1_GOT_DIGIT1:
if (c == START_FRAME_DIGIT2) {
*state = STATE2_GOT_DIGIT2;
//printf("Got SFD2 \n");
}
case STATE3_GOT_MSB_DATA:
*state = STATE4_GOT_LSB_DATA;
parserbuf[DISTANCE_LSB_POS] = c; // LSB Data
//printf("Got DATA2 0x%02X \n", c);
// do crc calculation
*crc16 = crc16_calc(parserbuf, CHECKSUM_LENGTH);
// convert endian
*crc16 = (*crc16 >> 8) | (*crc16 << 8);
break;
// @NOTE: (claudio@auterion.com): if second byte is wrong we skip all the frame and restart parsing !!
else if (c == START_FRAME_DIGIT1) {
*state = STATE1_GOT_DIGIT1;
//printf("Discard previous SFD1, Got new SFD1 \n");
} else {
*state = STATE0_WAITING_FRAME;
}
break;
case STATE2_GOT_DIGIT2:
*state = STATE3_GOT_MSB_DATA;
parserbuf[DISTANCE_MSB_POS] = c; // MSB Data
//printf("Got DATA1 0x%02X \n", c);
break;
case STATE3_GOT_MSB_DATA:
*state = STATE4_GOT_LSB_DATA;
parserbuf[DISTANCE_LSB_POS] = c; // LSB Data
//printf("Got DATA2 0x%02X \n", c);
// do crc calculation
*crc16 = crc16_calc(parserbuf, CHECKSUM_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;
case STATE4_GOT_LSB_DATA:
if (c == (*crc16 >> 8)) {
*state = STATE5_GOT_CHKSUM1;
}
break;
} else {
// printf("Checksum invalid on high byte: 0x%02X, calculated: 0x%04X \n",c, *crc16);
*state = STATE0_WAITING_FRAME;
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;
}
/*else {
//printf("Checksum invalidon low byte: 0x%02X, calculated: 0x%04X \n",c, *crc16);
}*/
break;
}
default:
printf("This should never happen. \n");
break;
}
break;
return ret;
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;
}
/*else {
//printf("Checksum invalidon low byte: 0x%02X, calculated: 0x%04X \n",c, *crc16);
}*/
break;
default:
printf("This should never happen. \n");
break;
}
return ret;
}

View File

@ -31,12 +31,12 @@
*
****************************************************************************/
/**
* @file cm8jl65.cpp
* @author Claudio Micheli <claudio@auterion.com>
*
* Parser declarations for Lanbao PSK-CM8JL65-CC5 distance sensor
*/
/**
* @file cm8jl65.cpp
* @author Claudio Micheli <claudio@auterion.com>
*
* Parser declarations for Lanbao PSK-CM8JL65-CC5 distance sensor
*/
#pragma once
@ -58,15 +58,15 @@
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,
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,enum CM8JL65_PARSE_STATE *state,uint16_t *crc16, int *dist);
int cm8jl65_parser(uint8_t c, uint8_t *parserbuf, enum CM8JL65_PARSE_STATE *state, uint16_t *crc16, int *dist);