/* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ #include #include "AP_RangeFinder_insighticaSerial.h" #include #include #include "stdio.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_insighticaSerial::AP_RangeFinder_insighticaSerial(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params, uint8_t serial_instance) : AP_RangeFinder_Backend(_state, _params) { const AP_SerialManager &serial_manager = AP::serialmanager(); uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance); if (uart != nullptr) { uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance)); } } /* detect if a insightica rangefinder is connected. We'll detect by trying to take a reading on Serial. If we get a result the sensor is there. */ bool AP_RangeFinder_insighticaSerial::detect(uint8_t serial_instance) { return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr; } const int StartSequence=0xAA; //数据包帧头 const int EndSequence=0X55; // read - return last value measured by sensor // bool AP_RangeFinder_insighticaSerial::get_reading(uint16_t &reading_cm,uint16_t &testdata) bool AP_RangeFinder_insighticaSerial::get_reading(uint16_t &reading_cm) { if (uart == nullptr) { return false; } // read any available lines from the lidar uint8_t frameOK = 0; uint16_t Range = 0; //雷达实测距离 int16_t nbytes = uart->available(); while ( nbytes-- > 0 ) { if( uart->read() == StartSequence ){ //判断数据包帧头0xAA string[0] = StartSequence; if( uart->read() == StartSequence ){ //判断数据包帧头0xAA string[1] = StartSequence; for( int i = 2;i < 14;i++ ){ //存储数据到数组 string[i] = uart->read(); } CheckSum = string[4]+string[5]+string[6]+string[7]+string[8]+string[9]+string[10]; if( string[11] == (CheckSum&0xFF)&&string[12] == EndSequence && string[13] == EndSequence ){ //按照协议对收到的数据进行校验 frameOK = 1; Range = (string[6]*256+string[7]); //cm // testdata = (string[8]*256+string[9]); } } } } if (frameOK == 0) { return false; } if(Range != 0) { reading_cm = Range; } return true; } /* update the state of the sensor ****** this is used by the up code of sensors.cpp */ void AP_RangeFinder_insighticaSerial::update(void) { if (get_reading(state.distance_cm)) { // update range_valid state based on distance measured state.last_reading_ms = AP_HAL::millis(); update_status(); } else if (AP_HAL::millis() - state.last_reading_ms > 500) { set_status(RangeFinder::RangeFinder_NoData); } }