2018-06-15 06:08:01 -03:00
|
|
|
/*
|
|
|
|
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 <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include "AP_Proximity_TeraRangerTowerEvo.h"
|
|
|
|
#include <AP_Math/crc.h>
|
|
|
|
#include <ctype.h>
|
|
|
|
#include <stdio.h>
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
// update the state of the sensor
|
|
|
|
void AP_Proximity_TeraRangerTowerEvo::update(void)
|
|
|
|
{
|
2019-12-04 00:57:16 -04:00
|
|
|
if (_uart == nullptr) {
|
2018-06-15 06:08:01 -03:00
|
|
|
return;
|
|
|
|
}
|
2019-12-04 00:57:16 -04:00
|
|
|
if (_last_request_sent_ms == 0) {
|
|
|
|
_last_request_sent_ms = AP_HAL::millis();
|
|
|
|
}
|
2018-06-15 06:08:01 -03:00
|
|
|
//initialize the sensor
|
|
|
|
if(_current_init_state != InitState::InitState_Finished)
|
|
|
|
{
|
|
|
|
initialise_modes();
|
|
|
|
}
|
|
|
|
|
|
|
|
// process incoming messages
|
|
|
|
read_sensor_data();
|
|
|
|
|
|
|
|
// check for timeout and set health status
|
|
|
|
if ((_last_distance_received_ms == 0) || (AP_HAL::millis() - _last_distance_received_ms > PROXIMITY_TRTOWER_TIMEOUT_MS)) {
|
2019-09-27 05:58:52 -03:00
|
|
|
set_status(AP_Proximity::Status::NoData);
|
2018-06-15 06:08:01 -03:00
|
|
|
} else {
|
2019-09-27 05:58:52 -03:00
|
|
|
set_status(AP_Proximity::Status::Good);
|
2018-06-15 06:08:01 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// get maximum and minimum distances (in meters) of primary sensor
|
|
|
|
float AP_Proximity_TeraRangerTowerEvo::distance_max() const
|
|
|
|
{
|
2018-07-25 05:57:14 -03:00
|
|
|
return 60.0f;
|
2018-06-15 06:08:01 -03:00
|
|
|
}
|
|
|
|
float AP_Proximity_TeraRangerTowerEvo::distance_min() const
|
|
|
|
{
|
2018-07-25 05:57:14 -03:00
|
|
|
return 0.50f;
|
2018-06-15 06:08:01 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void AP_Proximity_TeraRangerTowerEvo::initialise_modes()
|
|
|
|
{
|
|
|
|
if((AP_HAL::millis() - _last_request_sent_ms) < _mode_request_delay) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_current_init_state == InitState_Printout) {
|
|
|
|
set_mode(BINARY_MODE, 4);
|
2018-06-20 07:31:29 -03:00
|
|
|
} else if (_current_init_state == InitState_Sequence) {
|
2018-06-15 06:08:01 -03:00
|
|
|
//set tower mode - 4 sensors are triggered at once with 90 deg angle between each sensor
|
2018-06-15 07:15:58 -03:00
|
|
|
set_mode(TOWER_MODE, 4);
|
2018-06-15 06:08:01 -03:00
|
|
|
} else if (_current_init_state == InitState_Rate) {
|
2018-06-15 07:15:58 -03:00
|
|
|
//set update rate of the sensor.
|
2018-06-20 07:31:29 -03:00
|
|
|
set_mode(REFRESH_100_HZ, 5);
|
2018-06-15 06:08:01 -03:00
|
|
|
} else if (_current_init_state == InitState_StreamStart) {
|
|
|
|
set_mode(ACTIVATE_STREAM, 5);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void AP_Proximity_TeraRangerTowerEvo::set_mode(const uint8_t *c, int length)
|
|
|
|
{
|
2019-12-04 00:57:16 -04:00
|
|
|
_uart->write(c, length);
|
2018-06-15 06:08:01 -03:00
|
|
|
_last_request_sent_ms = AP_HAL::millis();
|
|
|
|
}
|
|
|
|
|
|
|
|
// check for replies from sensor, returns true if at least one message was processed
|
|
|
|
bool AP_Proximity_TeraRangerTowerEvo::read_sensor_data()
|
|
|
|
{
|
2019-12-04 00:57:16 -04:00
|
|
|
if (_uart == nullptr) {
|
2018-06-15 06:08:01 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint16_t message_count = 0;
|
2019-12-04 00:57:16 -04:00
|
|
|
int16_t nbytes = _uart->available();
|
2018-06-15 06:08:01 -03:00
|
|
|
|
2018-06-20 07:31:29 -03:00
|
|
|
if(_current_init_state != InitState_Finished && nbytes == 4) {
|
|
|
|
|
|
|
|
//Increment _current_init_state only when we receive 4 ack bytes
|
|
|
|
switch (_current_init_state) {
|
|
|
|
case InitState_Printout:
|
|
|
|
_current_init_state = InitState_Sequence;
|
|
|
|
break;
|
|
|
|
case InitState_Sequence:
|
|
|
|
_current_init_state = InitState_Rate;
|
|
|
|
break;
|
|
|
|
case InitState_Rate:
|
|
|
|
_current_init_state = InitState_StreamStart;
|
|
|
|
break;
|
|
|
|
case InitState_StreamStart:
|
|
|
|
_current_init_state = InitState_Finished;
|
|
|
|
break;
|
|
|
|
case InitState_Finished:
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
2018-07-25 05:57:14 -03:00
|
|
|
|
2018-06-15 06:08:01 -03:00
|
|
|
while (nbytes-- > 0) {
|
2019-12-04 00:57:16 -04:00
|
|
|
char c = _uart->read();
|
2018-06-15 06:08:01 -03:00
|
|
|
if (c == 'T' ) {
|
|
|
|
buffer_count = 0;
|
|
|
|
}
|
|
|
|
buffer[buffer_count++] = c;
|
|
|
|
|
|
|
|
// we should always read 19 bytes THxxxxxxxxxxxxxxxxMC
|
|
|
|
if (buffer_count >= 20){
|
|
|
|
buffer_count = 0;
|
2018-07-25 05:57:14 -03:00
|
|
|
|
2018-06-15 06:08:01 -03:00
|
|
|
//check if message has right CRC
|
|
|
|
if (crc_crc8(buffer, 19) == buffer[19]){
|
2019-03-27 08:10:57 -03:00
|
|
|
update_sector_data(0, UINT16_VALUE(buffer[2], buffer[3])); // d1
|
|
|
|
update_sector_data(45, UINT16_VALUE(buffer[4], buffer[5])); // d2
|
|
|
|
update_sector_data(90, UINT16_VALUE(buffer[6], buffer[7])); // d3
|
|
|
|
update_sector_data(135, UINT16_VALUE(buffer[8], buffer[9])); // d4
|
|
|
|
update_sector_data(180, UINT16_VALUE(buffer[10], buffer[11])); // d5
|
|
|
|
update_sector_data(225, UINT16_VALUE(buffer[12], buffer[13])); // d6
|
|
|
|
update_sector_data(270, UINT16_VALUE(buffer[14], buffer[15])); // d7
|
|
|
|
update_sector_data(315, UINT16_VALUE(buffer[16], buffer[17])); // d8
|
2018-06-15 06:08:01 -03:00
|
|
|
|
|
|
|
message_count++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return (message_count > 0);
|
|
|
|
}
|
|
|
|
|
|
|
|
// process reply
|
|
|
|
void AP_Proximity_TeraRangerTowerEvo::update_sector_data(int16_t angle_deg, uint16_t distance_cm)
|
|
|
|
{
|
2019-12-03 22:46:03 -04:00
|
|
|
const uint8_t sector = convert_angle_to_sector(angle_deg);
|
|
|
|
_angle[sector] = angle_deg;
|
|
|
|
_distance[sector] = ((float) distance_cm) / 1000;
|
|
|
|
|
|
|
|
//check for target too far, target too close and sensor not connected
|
|
|
|
_distance_valid[sector] = distance_cm != 0xffff && distance_cm != 0x0000 && distance_cm != 0x0001;
|
|
|
|
_last_distance_received_ms = AP_HAL::millis();
|
|
|
|
// update boundary used for avoidance
|
|
|
|
update_boundary_for_sector(sector, true);
|
2018-06-15 06:08:01 -03:00
|
|
|
}
|