Browse Source

Added TI PGA460 driver functionality to PX4.

sbg
Jake Dahl 7 years ago committed by Lorenz Meier
parent
commit
07d606ef83
  1. 6
      ROMFS/px4fmu_common/init.d/rc.sensors
  2. 1
      src/drivers/distance_sensor/CMakeLists.txt
  3. 43
      src/drivers/distance_sensor/pga460/CMakeLists.txt
  4. 42
      src/drivers/distance_sensor/pga460/parameters.c
  5. 851
      src/drivers/distance_sensor/pga460/pga460.cpp
  6. 412
      src/drivers/distance_sensor/pga460/pga460.h

6
ROMFS/px4fmu_common/init.d/rc.sensors

@ -398,6 +398,12 @@ then @@ -398,6 +398,12 @@ then
ll40ls start i2c
fi
# pga460 sonar sensor
if param greater SENS_EN_PGA460 0
then
pga460 start
fi
# Lightware serial lidar sensor
if param greater SENS_EN_SF0X 0
then

1
src/drivers/distance_sensor/CMakeLists.txt

@ -42,3 +42,4 @@ add_subdirectory(tfmini) @@ -42,3 +42,4 @@ add_subdirectory(tfmini)
add_subdirectory(ulanding)
add_subdirectory(leddar_one)
add_subdirectory(vl53lxx)
add_subdirectory(pga460)

43
src/drivers/distance_sensor/pga460/CMakeLists.txt

@ -0,0 +1,43 @@ @@ -0,0 +1,43 @@
############################################################################
#
# Copyright (c) 2016 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.
#
############################################################################
px4_add_module(
MODULE drivers__pga460
MAIN pga460
COMPILE_FLAGS
-Os
SRCS
pga460.cpp
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

42
src/drivers/distance_sensor/pga460/parameters.c

@ -0,0 +1,42 @@ @@ -0,0 +1,42 @@
/****************************************************************************
*
* Copyright (c) 2017 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.
*
****************************************************************************/
/**
* PGA460 Ultrasonic driver (PGA460)
*
* @reboot_required true
*
* @boolean
* @group Sensors
*/
PARAM_DEFINE_INT32(SENS_EN_PGA460, 0);

851
src/drivers/distance_sensor/pga460/pga460.cpp

@ -0,0 +1,851 @@ @@ -0,0 +1,851 @@
/****************************************************************************
*
* Copyright (c) 2012-2016 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 pga460.cpp
* @author Jacob Dahl <jacob.dahl@tealdrones.com>
*
* Driver for the TI PGA460 Ultrasonic Signal Processor and Transducer Driver
*/
#include "pga460.h"
extern "C" __EXPORT int pga460_main(int argc, char *argv[]);
PGA460::PGA460(const char *port)
{
// Store port name.
strncpy(_port, port, sizeof(_port));
// Enforce null termination.
_port[sizeof(_port) - 1] = '\0';
}
PGA460::~PGA460()
{
orb_unadvertise(_distance_sensor_topic);
}
uint8_t PGA460::calc_checksum(uint8_t *data, const uint8_t size)
{
uint8_t checksum_input[size];
for (size_t i = 0; i < size; i++) {
checksum_input[i] = *data;
data++;
}
uint16_t carry = 0;
for (uint8_t j = 0; j < size; j++) {
if ((checksum_input[j] + carry) < carry) {
carry = carry + checksum_input[j] + 1;
} else {
carry = carry + checksum_input[j];
}
if (carry > 0xFF) {
carry = carry - 255;
}
}
carry = (~carry & 0x00FF);
return carry;
}
int PGA460::close_serial()
{
int ret = px4_close(_fd);
if (ret != 0) {
PX4_WARN("Could not close serial port");
}
return ret;
}
int PGA460::custom_command(int argc, char *argv[])
{
return print_usage("Unrecognized command.");
}
PGA460 *PGA460::instantiate(int argc, char *argv[])
{
PGA460 *pga460 = new PGA460(PGA460_DEFAULT_PORT);
return pga460;
}
int PGA460::initialize_device_settings()
{
if (initialize_thresholds() != PX4_OK) {
PX4_WARN("Thresholds not initialized");
return PX4_ERROR;
}
usleep(10000);
// Read to see if eeprom saved data matches desired data, otherwise overwrite eeprom.
if (read_eeprom() != PX4_OK) {
write_eeprom();
}
// Allow sufficient time for the device to complete writing to registers.
usleep(10000);
// Verify the device is alive.
if (read_register(0x00) != USER_DATA1) {
close_serial();
return PX4_ERROR;
}
return PX4_OK;
}
int PGA460::initialize_thresholds()
{
const uint8_t array_size = 35;
uint8_t settings_buf[array_size] = {SYNCBYTE, BC_THRBW,
P1_THR_0, P1_THR_1, P1_THR_2, P1_THR_3, P1_THR_4, P1_THR_5,
P1_THR_6, P1_THR_7, P1_THR_8, P1_THR_9, P1_THR_10,
P1_THR_11, P1_THR_12, P1_THR_13, P1_THR_14, P1_THR_15,
P2_THR_0, P2_THR_1, P2_THR_2, P2_THR_3, P2_THR_4, P2_THR_5,
P2_THR_6, P2_THR_7, P2_THR_8, P2_THR_9, P2_THR_10,
P2_THR_11, P2_THR_12, P2_THR_13, P2_THR_14, P2_THR_15, 0xFF
};
uint8_t checksum = calc_checksum(&settings_buf[1], sizeof(settings_buf) - 2);
settings_buf[array_size - 1] = checksum;
px4_write(_fd, &settings_buf[0], sizeof(settings_buf));
// Must wait >50us per datasheet.
usleep(100);
if (read_threshold_registers()) {
return 1;
} else {
print_device_status();
return 0;
}
}
uint32_t PGA460::collect_results()
{
px4_pollfd_struct_t fds[1];
fds[0].fd = _fd;
fds[0].events = POLLIN;
int timeout = 10;
uint8_t buf_rx[6] = {0};
int ret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), timeout);
// Waiting for a maximum of 10ms.
if (ret > 0) {
usleep(10000);
px4_read(_fd, buf_rx, sizeof(buf_rx));
} else {
PX4_WARN("px4_poll() failed");
}
uint16_t time_of_flight = (buf_rx[1] << 8) + buf_rx[2];
uint8_t Width = buf_rx[3];
uint8_t Amplitude = buf_rx[4];
float object_distance = calculate_object_distance(time_of_flight);
uORB_publish_results(object_distance);
// B1,2: time_of_flight B3: Width B4: Amplitude
uint32_t results = (time_of_flight << 16) | (Width << 8) | (Amplitude << 0);
return results;
}
float PGA460::calculate_object_distance(uint16_t time_of_flight)
{
float temperature = get_temperature();
// Default temperature if no temperature measurement can be obtained.
if (temperature > MAX_DETECTABLE_TEMPERATURE ||
temperature < MIN_DETECTABLE_TEMPERATURE) {
temperature = 20.0f;
}
// Formula for the speed of sound over temperature: v = 331m/s + 0.6m/s/C * T
float speed_of_sound = 331.0f + 0.6f * temperature;
float millseconds_to_meters = 0.000001f;
// Calculate the object distance in meters.
float object_distance = (float)time_of_flight * millseconds_to_meters * (speed_of_sound / 2.0f);
return object_distance;
}
void PGA460::flash_eeprom()
{
// Send same unlock code with prog bit set to 1.
uint8_t eeprom_write_buf[5] = {SYNCBYTE, SRW, EE_CNTRL_ADDR, EE_UNLOCK_ST2, 0xFF};
uint8_t checksum = calc_checksum(&eeprom_write_buf[1], sizeof(eeprom_write_buf) - 2);
eeprom_write_buf[4] = checksum;
px4_write(_fd, &eeprom_write_buf[0], sizeof(eeprom_write_buf));
}
float PGA460::get_temperature()
{
uint8_t buf_tx[4] = {SYNCBYTE, TNLM, 0x00, 0xFF};
uint8_t checksum = calc_checksum(&buf_tx[0], 3);
buf_tx[3] = checksum;
px4_write(_fd, &buf_tx[0], sizeof(buf_tx));
// The pga460 requires a 2ms delay per the datasheet.
usleep(2000);
buf_tx[1] = TNLR;
px4_write(_fd, &buf_tx[0], sizeof(buf_tx) - 2);
px4_pollfd_struct_t fds[1];
fds[0].fd = _fd;
fds[0].events = POLLIN;
int bytesread = 0;
int timeout = 10; // Wait up to 10ms inbetween bytes.
uint8_t buf_rx[4] = {0};
int ret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), timeout);
while (ret) {
if (fds[0].revents & POLLIN) {
bytesread += px4_read(_fd, buf_rx + bytesread, sizeof(buf_rx) - bytesread);
} else { break; }
ret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), timeout);
}
// These constants and equations are from the pga460 datasheet, page 50.
float juntion_to_ambient_thermal_resistance = 96.1;
float v_power = 16.5;
float supply_current_listening = 0.012;
float temperature = ((buf_rx[1] - 64) / 1.5f) -
(juntion_to_ambient_thermal_resistance * supply_current_listening * v_power);
return temperature;
}
int PGA460::open_serial()
{
_fd = px4_open(_port, O_RDWR | O_NOCTTY | O_NONBLOCK);
if (_fd < 0) {
PX4_WARN("Failed to open serial port");
return PX4_ERROR;
}
struct termios uart_config;
int termios_state;
// Fill the struct for the new configuration.
tcgetattr(_fd, &uart_config);
// Input flags - Turn off input processing:
// convert break to null byte, no CR to NL translation,
// no NL to CR translation, don't mark parity errors or breaks
// no input parity check, don't strip high bit off,
// no XON/XOFF software flow control
//
uart_config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL | INLCR | IGNCR | PARMRK | INPCK | ISTRIP | IXON | IXOFF);
uart_config.c_iflag |= IGNPAR;
// Output flags - Turn off output processing:
// no CR to NL translation, no NL to CR-NL translation,
// no NL to CR translation, no column 0 CR suppression,
// no Ctrl-D suppression, no fill characters, no case mapping,
// no local output processing
uart_config.c_oflag &= ~(OCRNL | ONLCR | ONLRET | ONOCR | OFILL | OPOST);
// No line processing:
// echo off, echo newline off, canonical mode off,
// extended input processing off, signal chars off
uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
// No parity, one stop bit, disable flow control.
uart_config.c_cflag &= ~(CSIZE | PARENB | CSTOPB | CRTSCTS);
uart_config.c_cflag |= (CS8 | CREAD | CLOCAL);
uart_config.c_cc[VMIN] = 1;
uart_config.c_cc[VTIME] = 0;
unsigned speed = 115200;
// Set the baud rate.
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
PX4_WARN("ERR CFG: %d ISPD", termios_state);
return PX4_ERROR;
}
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
PX4_WARN("ERR CFG: %d OSPD\n", termios_state);
return PX4_ERROR;
}
if ((termios_state = tcsetattr(_fd, TCSANOW, &uart_config)) < 0) {
PX4_WARN("ERR baud %d ATTR", termios_state);
return PX4_ERROR;
}
return _fd;
}
void PGA460::print_device_status()
{
uint8_t status_flags1 = read_register(0x4C);
uint8_t status_flags2 = read_register(0x4D);
if ((status_flags1 & 0x0F) || status_flags2) {
if (status_flags1 & 0x0F & 1) {
PX4_INFO("Trim EEPROM space data CRC error");
}
if (status_flags1 & 0x0F & 1 << 1) {
PX4_INFO("User EEPROM space data CRC error");
}
if (status_flags1 & 0x0F & 1 << 2) {
PX4_INFO("Threshold map configuration register data CRC error");
}
if (status_flags1 & 0x0F & 1 << 3) {
PX4_INFO("Wakeup Error");
}
if (status_flags2 & 1) {
PX4_INFO("VPWR pin under voltage");
}
if (status_flags2 & 1 << 1) {
PX4_INFO("VPWR pin over voltage");
}
if (status_flags2 & 1 << 2) {
PX4_INFO("AVDD pin under voltage");
}
if (status_flags2 & 1 << 3) {
PX4_INFO("AVDD pin over voltage");
}
if (status_flags2 & 1 << 4) {
PX4_INFO("IOREG pin under voltage");
}
if (status_flags2 & 1 << 5) {
PX4_INFO("IOREG pin over voltage");
}
if (status_flags2 & 1 << 6) {
PX4_INFO("Thermal shutdown has occured");
}
}
}
void PGA460::print_diagnostics(const uint8_t diagnostic_byte)
{
// Check the diagnostics bit field.
if (diagnostic_byte & 1 << 6) {
if (diagnostic_byte & 1 << 0) {
PX4_INFO("Device busy");
}
if (diagnostic_byte & 1 << 1) {
PX4_INFO("Sync field bit rate too high/low");
}
if (diagnostic_byte & 1 << 2) {
PX4_INFO("Consecutive sync bit fields do not match");
}
if (diagnostic_byte & 1 << 3) {
PX4_INFO("Invalid checksum");
}
if (diagnostic_byte & 1 << 4) {
PX4_INFO("Invalid command");
}
if (diagnostic_byte & 1 << 5) {
PX4_INFO("General comm erorr");
}
} else if (diagnostic_byte & 1 << 7) {
if (diagnostic_byte & 1 << 0) {
PX4_INFO("Device busy");
}
if (diagnostic_byte & 1 << 1) {
PX4_INFO("Threshold settings CRC error");
}
if (diagnostic_byte & 1 << 2) {
PX4_INFO("Frequency diagnostics error");
}
if (diagnostic_byte & 1 << 3) {
PX4_INFO("Voltage diagnostics error");
}
if (diagnostic_byte & 1 << 4) {
PX4_INFO("Always zero....");
}
if (diagnostic_byte & 1 << 5) {
PX4_INFO("EEPROM CRC or TRIM CRC error");
}
}
}
int PGA460::print_status()
{
PX4_INFO("Distance: %2.2f", (double)_previous_valid_report_distance);
return PX4_OK;
}
int PGA460::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
}
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
Ultrasonic range finder driver that handles the communication with the device and publishes the distance via uORB.
### Implementation
This driver is implented as a NuttX task. This Implementation was chosen due to the need for polling on a message
via UART, which is not supported in the work_queue. This driver continuously takes range measurements while it is
running. A simple algorithm to detect false readings is implemented at the driver levelin an attemptto improve
the quality of data that is being published. The driver will not publish data at all if it deems the sensor data
to be invalid or unstable.
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("pga460", "driver");
PRINT_MODULE_USAGE_COMMAND("start <device_path>");
PRINT_MODULE_USAGE_ARG("device_path", "The pga460 sensor device path, (e.g: /dev/ttyS6", true);
PRINT_MODULE_USAGE_COMMAND("status");
PRINT_MODULE_USAGE_COMMAND("stop");
PRINT_MODULE_USAGE_COMMAND("help");
return PX4_OK;
}
int PGA460::read_eeprom()
{
unlock_eeprom();
const int array_size = 43;
const uint8_t user_settings[array_size] =
{USER_DATA1, USER_DATA2, USER_DATA3, USER_DATA4,
USER_DATA5, USER_DATA6, USER_DATA7, USER_DATA8, USER_DATA9, USER_DATA10,
USER_DATA11, USER_DATA12, USER_DATA13, USER_DATA14, USER_DATA15, USER_DATA16,
USER_DATA17, USER_DATA18, USER_DATA19, USER_DATA20,
TVGAIN0, TVGAIN1, TVGAIN2, TVGAIN3, TVGAIN4, TVGAIN5, TVGAIN6, INIT_GAIN, FREQUENCY, DEADTIME,
PULSE_P1, PULSE_P2, CURR_LIM_P1, CURR_LIM_P2, REC_LENGTH, FREQ_DIAG, SAT_FDIAG_TH, FVOLT_DEC, DECPL_TEMP,
DSP_SCALE, TEMP_TRIM, P1_GAIN_CTRL, P2_GAIN_CTRL};
px4_pollfd_struct_t fds[1];
fds[0].fd = _fd;
fds[0].events = POLLIN;
int ret = -1;
int read_result = 0;
int timeout = 100;
size_t bytes_read = 0;
uint8_t cmd_buf[2] = {SYNCBYTE, EEBR};
uint8_t buf_rx[array_size + 2] = {0};
// The pga460 responds to this write() call by reporting current eeprom values.
ret = px4_write(_fd, &cmd_buf[0], sizeof(cmd_buf));
if (ret < 0) {
PX4_WARN("px4_write() failed.");
}
usleep(1000); // Sleep for 1ms to allow write to complete before polling.
ret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), timeout);
usleep(1000); // Sleep for 1ms to allow data to be received.
if (ret < 0) {
PX4_WARN("px4_poll() failed.");
return PX4_ERROR;
}
while (bytes_read < sizeof(buf_rx)) {
if (fds[0].revents & POLLIN) {
read_result = px4_read(_fd, buf_rx + bytes_read, sizeof(buf_rx) - bytes_read);
if (read_result >= 0) {
bytes_read += read_result;
} else {
return PX4_ERROR;
}
} else {
break;
}
ret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), timeout);
if (ret < 0) {
PX4_WARN("px4_poll() failed.");
break;
}
}
// Check the buffers to ensure they match.
int mismatched_bytes = memcmp(buf_rx + 1, user_settings, array_size);
if (mismatched_bytes == 0) {
return PX4_OK;
} else {
print_diagnostics(buf_rx[0]);
return PX4_ERROR;
}
}
uint8_t PGA460::read_register(const uint8_t reg)
{
// must unlock the eeprom registers before you can read or write to them
if (reg < 0x40) {
unlock_eeprom();
}
uint8_t buf_tx[4] = {SYNCBYTE, SRR, reg, 0xFF};
uint8_t checksum = calc_checksum(&buf_tx[1], 2);
buf_tx[3] = checksum;
px4_write(_fd, &buf_tx[0], sizeof(buf_tx));
px4_pollfd_struct_t fds[1];
fds[0].fd = _fd;
fds[0].events = POLLIN;
int timeout = 100;
int bytesread = 0;
uint8_t buf_rx[3] = {0};
int ret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
while (ret) {
if (fds[0].revents & POLLIN) {
bytesread += px4_read(_fd, buf_rx + bytesread, sizeof(buf_rx) - bytesread);
} else { break; }
ret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), timeout);
}
// Prints errors if there are any.
print_diagnostics(buf_rx[0]);
return buf_rx[1];
}
int PGA460::read_threshold_registers()
{
const int array_size = 32;
uint8_t user_settings[array_size] = {P1_THR_0, P1_THR_1, P1_THR_2, P1_THR_3, P1_THR_4,
P1_THR_5, P1_THR_6, P1_THR_7, P1_THR_8, P1_THR_9, P1_THR_10, P1_THR_11,
P1_THR_12, P1_THR_13, P1_THR_14, P1_THR_15,
P2_THR_0, P2_THR_1, P2_THR_2, P2_THR_3, P2_THR_4, P2_THR_5, P2_THR_6,
P2_THR_7, P2_THR_8, P2_THR_9, P2_THR_10, P2_THR_11, P2_THR_12, P2_THR_13,
P2_THR_14, P2_THR_15
};
uint8_t buf_tx[2] = {SYNCBYTE, THRBR};
px4_write(_fd, &buf_tx[0], sizeof(buf_tx));
px4_pollfd_struct_t fds[1];
fds[0].fd = _fd;
fds[0].events = POLLIN;
int timeout = 100;
int bytesread = 0;
uint8_t buf_rx[array_size + 2] = {0};
int ret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
while (ret) {
if (fds[0].revents & POLLIN) {
bytesread += px4_read(_fd, buf_rx + bytesread, sizeof(buf_rx) - bytesread);
} else { break; }
ret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), timeout);
}
// Check to ensure the buffers match.
int mismatch = memcmp(buf_rx + 1, user_settings, sizeof(buf_rx) - 2);
if (mismatch == 0) {
PX4_INFO("Threshold registers have program settings");
return PX4_OK;
} else {
PX4_WARN("Threshold registers do not have program settings");
print_diagnostics(buf_rx[0]);
return PX4_ERROR;
}
}
void PGA460::request_results()
{
uint8_t buf_tx[2] = {SYNCBYTE, UMR};
px4_write(_fd, &buf_tx[0], sizeof(buf_tx));
}
void PGA460::run()
{
open_serial();
initialize_device_settings();
struct distance_sensor_s report = {};
_distance_sensor_topic = orb_advertise(ORB_ID(distance_sensor), &report);
if (_distance_sensor_topic == nullptr) {
PX4_WARN("Failed to advertise distance_sensor topic. Did you start uORB?");
return;
}
_start_loop = hrt_absolute_time();
while (!should_exit()) {
// Check last report to determine if we need to switch range modes.
uint8_t mode = set_range_mode();
take_measurement(mode);
// Control rate.
uint64_t loop_time = hrt_absolute_time() - _start_loop;
uint32_t sleep_time = (loop_time > POLL_RATE_US) ? 0 : POLL_RATE_US - loop_time;
usleep(sleep_time);
_start_loop = hrt_absolute_time();
request_results();
collect_results();
}
PX4_INFO("Exiting.");
close_serial();
}
uint8_t PGA460::set_range_mode()
{
// Set the ASICs settings depening on the distance read from our last report.
if (_previous_valid_report_distance > (MODE_SET_THRESH + MODE_SET_HYST)) {
_ranging_mode = MODE_LONG_RANGE;
} else if (_previous_valid_report_distance < (MODE_SET_THRESH - MODE_SET_HYST)) {
_ranging_mode = MODE_SHORT_RANGE;
}
return _ranging_mode;
}
void PGA460::take_measurement(const uint8_t mode)
{
// Issue a measurement command to detect one object using Preset 1 Burst/Listen.
uint8_t buf_tx[4] = {SYNCBYTE, mode, 0x01, 0xFF};
uint8_t checksum = calc_checksum(&buf_tx[1], 2);
buf_tx[3] = checksum;
px4_write(_fd, &buf_tx[0], sizeof(buf_tx));
}
int PGA460::task_spawn(int argc, char *argv[])
{
px4_main_t entry_point = (px4_main_t)&run_trampoline;
int stack_size = 1256;
int task_id = px4_task_spawn_cmd("pga460", SCHED_DEFAULT,
SCHED_PRIORITY_SLOW_DRIVER, stack_size,
entry_point, (char *const *)argv);
if (task_id < 0) {
task_id = -1;
return -errno;
}
_task_id = task_id;
return PX4_OK;
}
void PGA460::uORB_publish_results(const float object_distance)
{
struct distance_sensor_s report = {};
report.timestamp = hrt_absolute_time();
report.type = distance_sensor_s::MAV_DISTANCE_SENSOR_ULTRASOUND;
report.orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
report.current_distance = object_distance;
report.min_distance = MIN_DETECTABLE_DISTANCE;
report.max_distance = MAX_DETECTABLE_DISTANCE;
report.signal_quality = 0;
bool data_is_valid = false;
static uint8_t good_data_counter = 0;
// If we are within our MIN and MAX thresholds, continue.
if (object_distance > MIN_DETECTABLE_DISTANCE && object_distance < MAX_DETECTABLE_DISTANCE) {
// Height cannot change by more than MAX_SAMPLE_DEVIATION between measurements.
bool sample_deviation_valid = (report.current_distance < _previous_valid_report_distance + MAX_SAMPLE_DEVIATION)
&& (report.current_distance > _previous_valid_report_distance - MAX_SAMPLE_DEVIATION);
// Must have NUM_SAMPLES_CONSISTENT valid samples to be publishing.
if (sample_deviation_valid) {
good_data_counter++;
if (good_data_counter > NUM_SAMPLES_CONSISTENT - 1) {
good_data_counter = NUM_SAMPLES_CONSISTENT;
data_is_valid = true;
} else {
// Have not gotten NUM_SAMPLES_CONSISTENT consistently valid samples.
data_is_valid = false;
}
} else if (good_data_counter > 0) {
good_data_counter--;
} else {
// Reset our quality of data estimate after NUM_SAMPLES_CONSISTENT invalid samples.
_previous_valid_report_distance = _previous_report_distance;
}
_previous_report_distance = report.current_distance;
}
if (data_is_valid) {
report.signal_quality = 1;
_previous_valid_report_distance = report.current_distance;
orb_publish(ORB_ID(distance_sensor), _distance_sensor_topic, &report);
}
}
void PGA460::unlock_eeprom()
{
// Two step EEPROM unlock -- send unlock code w/ prog bit set to 0.
// This might actually be wrapped into command 11 (ee bulk write) but I am not sure.
uint8_t eeprom_write_buf[5] = {SYNCBYTE, SRW, EE_CNTRL_ADDR, EE_UNLOCK_ST1, 0xFF};
uint8_t checksum = calc_checksum(&eeprom_write_buf[1], sizeof(eeprom_write_buf) - 2);
eeprom_write_buf[4] = checksum;
px4_write(_fd, &eeprom_write_buf[0], sizeof(eeprom_write_buf));
}
int PGA460::write_eeprom()
{
uint8_t settings_buf[46] = {SYNCBYTE, EEBW, USER_DATA1, USER_DATA2, USER_DATA3, USER_DATA4,
USER_DATA5, USER_DATA6, USER_DATA7, USER_DATA8, USER_DATA9, USER_DATA10,
USER_DATA11, USER_DATA12, USER_DATA13, USER_DATA14, USER_DATA15, USER_DATA16,
USER_DATA17, USER_DATA18, USER_DATA19, USER_DATA20,
TVGAIN0, TVGAIN1, TVGAIN2, TVGAIN3, TVGAIN4, TVGAIN5, TVGAIN6, INIT_GAIN, FREQUENCY, DEADTIME,
PULSE_P1, PULSE_P2, CURR_LIM_P1, CURR_LIM_P2, REC_LENGTH, FREQ_DIAG, SAT_FDIAG_TH, FVOLT_DEC, DECPL_TEMP,
DSP_SCALE, TEMP_TRIM, P1_GAIN_CTRL, P2_GAIN_CTRL, 0xFF
};
uint8_t checksum = calc_checksum(&settings_buf[1], sizeof(settings_buf) - 2);
settings_buf[45] = checksum;
px4_write(_fd, &settings_buf[0], sizeof(settings_buf));
// Needs time, see datasheet timing requirements.
usleep(5000);
unlock_eeprom();
flash_eeprom();
usleep(5000);
uint8_t result = 0;
// Give up to 100ms for ee_cntrl register to reflect a successful eeprom write.
for (int i = 0; i < 100; i++) {
result = read_register(EE_CNTRL_ADDR);
usleep(1000);
if (result & 1 << 2) {
PX4_INFO("EEPROM write successful");
return PX4_OK;
}
}
PX4_WARN("Failed to write to EEPROM");
print_diagnostics(result);
return PX4_ERROR;
}
int PGA460::write_register(const uint8_t reg, const uint8_t val)
{
// Must unlock the eeprom registers before you can read or write to them.
if (reg < 0x40) {
unlock_eeprom();
}
uint8_t buf_tx[5] = {SYNCBYTE, SRW, reg, val, 0xFF};
uint8_t checksum = calc_checksum(&buf_tx[1], sizeof(buf_tx) - 2);
buf_tx[4] = checksum;
uint8_t ret = px4_write(_fd, &buf_tx[0], sizeof(buf_tx));
if (ret != sizeof(buf_tx)) {
return PX4_OK;
} else {
return PX4_ERROR;
}
}
int pga460_main(int argc, char *argv[])
{
return PGA460::main(argc, argv);
}

412
src/drivers/distance_sensor/pga460/pga460.h

@ -0,0 +1,412 @@ @@ -0,0 +1,412 @@
/****************************************************************************
*
* Copyright (c) 2012-2016 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 pga460.h
* @author Jacob Dahl <jacob.dahl@tealdrones.com>
*
* Driver for the TI PGA460 Ultrasonic Signal Processor and Transducer Driver
*/
#ifndef _PGA460_H
#define _PGA460_H
#include <cstring>
#include <termios.h>
#include <drivers/device/device.h>
#include <drivers/drv_hrt.h>
#include <uORB/topics/distance_sensor.h>
#include <px4_module.h>
#include <px4_module_params.h>
#include <px4_tasks.h>
#define PGA460_DEFAULT_PORT "/dev/ttyS6"
#define MAX_DETECTABLE_DISTANCE 3.0f
#define MIN_DETECTABLE_DISTANCE 0.05f
#define MAX_DETECTABLE_TEMPERATURE 100.0f
#define MIN_DETECTABLE_TEMPERATURE -20.0f
#define MODE_SET_THRESH 0.6f
#define MODE_SET_HYST 0.0f
#define MAX_SAMPLE_DEVIATION 0.15f
#define NUM_SAMPLES_CONSISTENT 5
// #define POLL_RATE_US 50000ULL
#define POLL_RATE_US 0ULL
#define MODE_SHORT_RANGE P1BL
#define MODE_LONG_RANGE P2BL
#define SYNCBYTE 0x55
// Define UART commands by name
// Single Address
#define P1BL 0x00 // Burst and Listen (Preset 1)
#define P2BL 0x01 // Burst and Listen (Preset 2)
#define P1LO 0x02 // Listen Only (Preset 1)
#define P2LO 0x03 // Listen Only (Preset 2)
#define TNLM 0x04 // Temperature and Noise-level measurement
#define UMR 0x05 // Ultrasonic Measurement Result
#define TNLR 0x06 // Temperature and noise level result
#define TEDD 0x07 // Transducer echo data dump
#define SD 0x08 // System diagnostics
#define SRR 0x09 // Register read
#define SRW 0x0A // Register write
#define EEBR 0x0B // EEPROM bulk read
#define EEBW 0x0C // EEPROM bulk write
#define TVGBR 0x0D // Time-varying-gain bulk read
#define TVGBW 0x0E // Time-varying-gain bulk write
#define THRBR 0x0F // Threshold bulk read
#define THRBW 0x10 // Threshold bulk write
// Broadcast -- device will execute command irrespecive of UART address field
#define BC_P1BL 0x11 // Burst and listen (Preset 1)
#define BC_P2BL 0x12 // Burst and listen (Preset 2)
#define BC_P1LO 0x13 // Listen only (Preset 1)
#define BC_P2LO 0x14 // Listen only (Preset 2)
#define BC_TNLM 0x15 // Temperature and noise-level measurement
#define BC_SRW 0x16 // Register write
#define BC_EEBW 0x17 // EEPROM bulk write
#define BC_TVGBW 0x18 // Time varying-gain bulk write
#define BC_THRBW 0x19 // Threshold bulk write
// Addresses and Settings
#define EE_CNTRL_ADDR 0x40
#define EE_UNLOCK_ST1 0x68
#define EE_UNLOCK_ST2 0x69
// EEPROM -- non-volatile
#define USER_DATA1 0xAA //reg addr 0x0
#define USER_DATA2 0x0 //reg addr 0x1
#define USER_DATA3 0x0 //reg addr 0x2
#define USER_DATA4 0x0 //reg addr 0x3
#define USER_DATA5 0x0 //reg addr 0x4
#define USER_DATA6 0x0 //reg addr 0x5
#define USER_DATA7 0x0 //reg addr 0x6
#define USER_DATA8 0x0 //reg addr 0x7
#define USER_DATA9 0x0 //reg addr 0x8
#define USER_DATA10 0x0 //reg addr 0x9
#define USER_DATA11 0x0 //reg addr 0x0A
#define USER_DATA12 0x0 //reg addr 0x0B
#define USER_DATA13 0x0 //reg addr 0x0C
#define USER_DATA14 0x0 //reg addr 0x0D
#define USER_DATA15 0x0 //reg addr 0x0E
#define USER_DATA16 0x0 //reg addr 0x0F
#define USER_DATA17 0x0 //reg addr 0x10
#define USER_DATA18 0x0 //reg addr 0x11
#define USER_DATA19 0x0 //reg addr 0x12
#define USER_DATA20 0x0 //reg addr 0x13
#define TVGAIN0 0x9D //reg addr 0x14
#define TVGAIN1 0xBD //reg addr 0x15
#define TVGAIN2 0xEF //reg addr 0x16
#define TVGAIN3 0x31 //reg addr 0x17
#define TVGAIN4 0x48 //reg addr 0x18
#define TVGAIN5 0x67 //reg addr 0x19
#define TVGAIN6 0xAC //reg addr 0x1A
#define INIT_GAIN 0x40 //reg addr 0x1B
#define FREQUENCY (uint8_t)(5*(_resonant_frequency - 30.0f)) //reg addr 0x1C
#define DEADTIME 0xF0 //reg addr 0x1D
#define PULSE_P1 0x0C //reg addr 0x1E
#define PULSE_P2 0x1F //reg addr 0x1F
#define CURR_LIM_P1 0x7F //reg addr 0x20
#define CURR_LIM_P2 0x7F //reg addr 0x21
#define REC_LENGTH 0x44 //reg addr 0x22
#define FREQ_DIAG 0x1B //reg addr 0x23
#define SAT_FDIAG_TH 0x2C //reg addr 0x24
#define FVOLT_DEC 0x7C //reg addr 0x25
#define DECPL_TEMP 0xDF //reg addr 0x26
#define DSP_SCALE 0x0 //reg addr 0x27
#define TEMP_TRIM 0x0 //reg addr 0x28
#define P1_GAIN_CTRL 0x0 //reg addr 0x29
#define P2_GAIN_CTRL 0x8 //reg addr 0x2A
#define EE_CRC 0x29 //reg addr 0x2B
// Register-based -- volatile
#define EE_CNTRL 0x0 //reg addr 0x40
#define BPF_A2_MSB 0x85 //reg addr 0x41
#define BPF_A2_LSB 0xEA //reg addr 0x42
#define BPF_A3_MSB 0xF9 //reg addr 0x43
#define BPF_A3_LSB 0xA5 //reg addr 0x44
#define BPF_B1_MSB 0x3 //reg addr 0x45
#define BPF_B1_LSB 0x2D //reg addr 0x46
#define LPF_A2_MSB 0x7E //reg addr 0x47
#define LPF_A2_LSB 0x67 //reg addr 0x48
#define LPF_B1_MSB 0x0 //reg addr 0x49
#define LPF_B1_LSB 0xCD //reg addr 0x4A
#define TEST_MUX 0x0 //reg addr 0x4B
#define DEV_STAT0 0x80 //reg addr 0x4C
#define DEV_STAT1 0x0 //reg addr 0x4D
// Register-based -- volatile
#define P1_THR_0 0x54 //reg addr 0x5F
#define P1_THR_1 0x5C //reg addr 0x60
#define P1_THR_2 0xBD //reg addr 0x61
#define P1_THR_3 0xE0 //reg addr 0x62
#define P1_THR_4 0x6 //reg addr 0x63
#define P1_THR_5 0xCF //reg addr 0x64
#define P1_THR_6 0xEE //reg addr 0x65
#define P1_THR_7 0x8E //reg addr 0x66
#define P1_THR_8 0x84 //reg addr 0x67
#define P1_THR_9 0xB6 //reg addr 0x68
#define P1_THR_10 0x5A //reg addr 0x69
#define P1_THR_11 0xFF //reg addr 0x6A
#define P1_THR_12 0xFF //reg addr 0x6B
#define P1_THR_13 0xFF //reg addr 0x6C
#define P1_THR_14 0xFF //reg addr 0x6D
#define P1_THR_15 0x0 //reg addr 0x6E
#define P2_THR_0 0xBA //reg addr 0x6F
#define P2_THR_1 0xCF //reg addr 0x70
#define P2_THR_2 0xFF //reg addr 0x71
#define P2_THR_3 0xF5 //reg addr 0x72
#define P2_THR_4 0x1A //reg addr 0x73
#define P2_THR_5 0x5F //reg addr 0x74
#define P2_THR_6 0xFA //reg addr 0x75
#define P2_THR_7 0xD6 //reg addr 0x76
#define P2_THR_8 0xB6 //reg addr 0x77
#define P2_THR_9 0x35 //reg addr 0x78
#define P2_THR_10 0xDF //reg addr 0x79
#define P2_THR_11 0xFF //reg addr 0x7A
#define P2_THR_12 0xFF //reg addr 0x7B
#define P2_THR_13 0xFF //reg addr 0x7C
#define P2_THR_14 0xFF //reg addr 0x7D
#define P2_THR_15 0x0 //reg addr 0x7E
#define THR_CRC 0x1D //reg addr 0x7F
class PGA460 : public ModuleBase<PGA460>
{
public:
PGA460(const char *port = PGA460_DEFAULT_PORT);
virtual ~PGA460();
/**
* @see ModuleBase::custom_command().
* @brief main Main entry point to the module that should be
* called directly from the module's main method.
* @param argc The input argument count.
* @param argv Pointer to the input argument array.
* @return Returns 0 iff successful, -1 otherwise.
*/
static int custom_command(int argc, char *argv[]);
/**
* @see ModuleBase::instantiate().
* @brief Instantiates the pga460 object.
* @param argc The input argument count.
* @param argv Pointer to the input argument array.
*/
static PGA460 *instantiate(int argc, char *argv[]);
/**
* @see ModuleBase::print_usage().
* @brief Prints the module usage to the nuttshell console.
* @param reason The requested reason for printing to console.
*/
static int print_usage(const char *reason = nullptr);
/**
* @see ModuleBase::task_spawn().
*/
static int task_spawn(int argc, char *argv[]);
/**
* @brief Closes the serial port.
* @return Returns 0 if success or ERRNO.
*/
int close_serial();
/**
* @brief Opens the serial port.
* @return Returns true if the open was successful or ERRNO.
*/
int open_serial();
/**
* @brief Reports the diagnostic data from device status registers 1 and 2 if there is anything to report.
*/
void print_device_status();
/**
* @brief Reports the diagnostic data the diagnostic byte (first byte from slave).
* @param diagnostic_byte The diagnostic byte that contains the bitflags.
*/
void print_diagnostics(const uint8_t diagnostic_byte);
/**
* Diagnostics - print some basic information about the driver.
*/
int print_status() override;
/**
* @brief Reads the threshold registers.
* @return Returns true if the threshold registers are set to default
*/
int read_threshold_registers();
/**
* @see ModuleBase::run().
*/
void run() override;
/**
* @brief Reads the EEPROM and checks to see if it matches the default parameters.
* @note This method is only called once at boot.
* @return Returns PX4_OK if the EEPROM has default values, PX4_ERROR otherwise.
*/
int read_eeprom();
/**
* @brief Writes the user defined paramaters to device EEPROM.
* @return Returns true if the EEPROM was successfully written to.
*/
int write_eeprom();
/**
* @brief Reads a register.
* @param reg The register to read from.
* @return Returns the value of the register at the specified address.
*/
uint8_t read_register(const uint8_t reg);
/**
* @brief Writes a value to a register.
* @param reg The register address to write to.
* @param val The value to write.
* @return Returns true for success or false for fail.
*/
int write_register(const uint8_t reg, const uint8_t val);
private:
/**
* @brief Calculates the checksum of the transmitted commmand + data.
* @param data Pointer to the data a checksum will be calculated for.
* @param size The size of the data (bytes) the checksum will be calculated for.
* @return Returns the single byte checksum.
*/
uint8_t calc_checksum(uint8_t *data, const uint8_t size);
/**
* @brief Calculates the distance from the measurement time of flight (time_of_flight) and current temperature.
* @param time_of_flight The reported time of flight in ms from the device.
* @return Returns the distance measurement in meters.
*/
float calculate_object_distance(uint16_t time_of_flight);
/**
* @brief Collects the data in the serial port rx buffer, does math, and publishes the value to uORB
* @return Returns the measurment results in format: (u16)time_of_flight, (u8)width, (u8)amplitude
*/
uint32_t collect_results();
/**
* @brief Send the program command to the EEPROM to start the flash process.
*/
void flash_eeprom();
/**
* @brief Writes program defined threshold defaults to the register map and checks/writes the EEPROM.
* @return Returns PX4_OK upon success or PX4_ERROR on fail.
*/
int initialize_device_settings();
/**
* @brief Writes the user defined paramaters to device register map.
* @return Returns true if the thresholds were successfully written.
*/
int initialize_thresholds();
/**
* @brief Measurement is read from UART RX buffer and published to the uORB distance sensor topic.
*/
void request_results();
/**
* @brief Checks the measurement from last report and sets the range distance mode (long range , short range).
* @return Returns the either P1Bl or P1B2. Preset 1 (P1BL) is short range mode and preset two (P2BL) is long range mode.
*/
uint8_t set_range_mode();
/**
* @brief Commands the device to perform an ultrasonic measurement.
*/
void take_measurement(const uint8_t mode);
/*
* @brief Gets a temperature measurement in degrees C.
* @return Returns the temperature measurement in degrees C.
*/
float get_temperature();
/**
* @brief Send the unlock command to the EEPROM to enable reading and writing -- not needed w/ bulk write
*/
void unlock_eeprom();
/**
* @brief Commands the device to publish the measurement results to uORB.
* @param dist The calculated distance to the object.
*/
void uORB_publish_results(const float dist);
/** @orb_advert_t orb_advert_t uORB advertisement topic. */
orb_advert_t _distance_sensor_topic = nullptr;
/** @param _fd Returns the file descriptor from px4_open(). */
int _fd = -1;
/** @param _port Stores the port name. */
char _port[20];
/** @param _previous_report_distance The previous reported sensor distance. */
float _previous_report_distance = 0;
/** @param _previous_valid_report_distance The previous valid reported sensor distance. */
float _previous_valid_report_distance = 0;
/** @param _resonant_frequency The sensor resonant (transmit) frequency. */
float _resonant_frequency = 41.0f;
/** @param _mode_long_range Flag for long range mode. If false, sensor is in short range mode. */
uint8_t _ranging_mode = MODE_SHORT_RANGE;
/** @param _start_loop The starting value for the loop time of the main loop. */
uint64_t _start_loop = 0;
};
#endif
Loading…
Cancel
Save