|
PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <cstring>#include <termios.h>#include <drivers/device/device.h>#include <drivers/drv_hrt.h>#include <uORB/topics/distance_sensor.h>#include <px4_platform_common/module.h>#include <px4_platform_common/module_params.h>#include <px4_platform_common/tasks.h>Go to the source code of this file.
Classes | |
| class | PGA460 |
Macros | |
| #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 0ULL |
| #define | MODE_SHORT_RANGE P1BL |
| #define | MODE_LONG_RANGE P2BL |
| #define | SYNCBYTE 0x55 |
| #define | P1BL 0x00 |
| #define | P2BL 0x01 |
| #define | P1LO 0x02 |
| #define | P2LO 0x03 |
| #define | TNLM 0x04 |
| #define | UMR 0x05 |
| #define | TNLR 0x06 |
| #define | TEDD 0x07 |
| #define | SD 0x08 |
| #define | SRR 0x09 |
| #define | SRW 0x0A |
| #define | EEBR 0x0B |
| #define | EEBW 0x0C |
| #define | TVGBR 0x0D |
| #define | TVGBW 0x0E |
| #define | THRBR 0x0F |
| #define | THRBW 0x10 |
| #define | BC_P1BL 0x11 |
| #define | BC_P2BL 0x12 |
| #define | BC_P1LO 0x13 |
| #define | BC_P2LO 0x14 |
| #define | BC_TNLM 0x15 |
| #define | BC_SRW 0x16 |
| #define | BC_EEBW 0x17 |
| #define | BC_TVGBW 0x18 |
| #define | BC_THRBW 0x19 |
| #define | EE_CNTRL_ADDR 0x40 |
| #define | EE_UNLOCK_ST1 0x68 |
| #define | EE_UNLOCK_ST2 0x69 |
| #define | USER_DATA1 0xAA |
| #define | USER_DATA2 0x0 |
| #define | USER_DATA3 0x0 |
| #define | USER_DATA4 0x0 |
| #define | USER_DATA5 0x0 |
| #define | USER_DATA6 0x0 |
| #define | USER_DATA7 0x0 |
| #define | USER_DATA8 0x0 |
| #define | USER_DATA9 0x0 |
| #define | USER_DATA10 0x0 |
| #define | USER_DATA11 0x0 |
| #define | USER_DATA12 0x0 |
| #define | USER_DATA13 0x0 |
| #define | USER_DATA14 0x0 |
| #define | USER_DATA15 0x0 |
| #define | USER_DATA16 0x0 |
| #define | USER_DATA17 0x0 |
| #define | USER_DATA18 0x0 |
| #define | USER_DATA19 0x0 |
| #define | USER_DATA20 0x0 |
| #define | TVGAIN0 0x9D |
| #define | TVGAIN1 0xBD |
| #define | TVGAIN2 0xEF |
| #define | TVGAIN3 0x31 |
| #define | TVGAIN4 0x48 |
| #define | TVGAIN5 0x67 |
| #define | TVGAIN6 0xAC |
| #define | INIT_GAIN 0x40 |
| #define | FREQUENCY (uint8_t)(5*(_resonant_frequency - 30.0f)) |
| #define | DEADTIME 0xF0 |
| #define | PULSE_P1 0x0C |
| #define | PULSE_P2 0x1F |
| #define | CURR_LIM_P1 0x7F |
| #define | CURR_LIM_P2 0x7F |
| #define | REC_LENGTH 0x44 |
| #define | FREQ_DIAG 0x1B |
| #define | SAT_FDIAG_TH 0x2C |
| #define | FVOLT_DEC 0x7C |
| #define | DECPL_TEMP 0xDF |
| #define | DSP_SCALE 0x0 |
| #define | TEMP_TRIM 0x0 |
| #define | P1_GAIN_CTRL 0x0 |
| #define | P2_GAIN_CTRL 0x8 |
| #define | EE_CRC 0x29 |
| #define | EE_CNTRL 0x0 |
| #define | BPF_A2_MSB 0x85 |
| #define | BPF_A2_LSB 0xEA |
| #define | BPF_A3_MSB 0xF9 |
| #define | BPF_A3_LSB 0xA5 |
| #define | BPF_B1_MSB 0x3 |
| #define | BPF_B1_LSB 0x2D |
| #define | LPF_A2_MSB 0x7E |
| #define | LPF_A2_LSB 0x67 |
| #define | LPF_B1_MSB 0x0 |
| #define | LPF_B1_LSB 0xCD |
| #define | TEST_MUX 0x0 |
| #define | DEV_STAT0 0x80 |
| #define | DEV_STAT1 0x0 |
| #define | P1_THR_0 0x54 |
| #define | P1_THR_1 0x5C |
| #define | P1_THR_2 0xBD |
| #define | P1_THR_3 0xE0 |
| #define | P1_THR_4 0x6 |
| #define | P1_THR_5 0xCF |
| #define | P1_THR_6 0xEE |
| #define | P1_THR_7 0x8E |
| #define | P1_THR_8 0x84 |
| #define | P1_THR_9 0xB6 |
| #define | P1_THR_10 0x5A |
| #define | P1_THR_11 0xFF |
| #define | P1_THR_12 0xFF |
| #define | P1_THR_13 0xFF |
| #define | P1_THR_14 0xFF |
| #define | P1_THR_15 0x0 |
| #define | P2_THR_0 0xBA |
| #define | P2_THR_1 0xCF |
| #define | P2_THR_2 0xFF |
| #define | P2_THR_3 0xF5 |
| #define | P2_THR_4 0x1A |
| #define | P2_THR_5 0x5F |
| #define | P2_THR_6 0xFA |
| #define | P2_THR_7 0xD6 |
| #define | P2_THR_8 0xB6 |
| #define | P2_THR_9 0x35 |
| #define | P2_THR_10 0xDF |
| #define | P2_THR_11 0xFF |
| #define | P2_THR_12 0xFF |
| #define | P2_THR_13 0xFF |
| #define | P2_THR_14 0xFF |
| #define | P2_THR_15 0x0 |
| #define | THR_CRC 0x1D |
Driver for the TI PGA460 Ultrasonic Signal Processor and Transducer Driver
Definition in file pga460.h.
| #define BC_THRBW 0x19 |
Definition at line 104 of file pga460.h.
Referenced by PGA460::initialize_thresholds().
| #define CURR_LIM_P1 0x7F |
Definition at line 144 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define CURR_LIM_P2 0x7F |
Definition at line 145 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define DEADTIME 0xF0 |
Definition at line 141 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define DECPL_TEMP 0xDF |
Definition at line 150 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define DSP_SCALE 0x0 |
Definition at line 151 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define EE_CNTRL_ADDR 0x40 |
Definition at line 107 of file pga460.h.
Referenced by PGA460::flash_eeprom(), PGA460::unlock_eeprom(), and PGA460::write_eeprom().
| #define EE_UNLOCK_ST1 0x68 |
Definition at line 108 of file pga460.h.
Referenced by PGA460::unlock_eeprom().
| #define EE_UNLOCK_ST2 0x69 |
Definition at line 109 of file pga460.h.
Referenced by PGA460::flash_eeprom().
| #define EEBR 0x0B |
Definition at line 88 of file pga460.h.
Referenced by PGA460::read_eeprom().
| #define EEBW 0x0C |
Definition at line 89 of file pga460.h.
Referenced by PGA460::write_eeprom().
| #define FREQ_DIAG 0x1B |
Definition at line 147 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define FREQUENCY (uint8_t)(5*(_resonant_frequency - 30.0f)) |
Definition at line 140 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define FVOLT_DEC 0x7C |
Definition at line 149 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define INIT_GAIN 0x40 |
Definition at line 139 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define MAX_DETECTABLE_DISTANCE 3.0f |
Definition at line 58 of file pga460.h.
Referenced by PGA460::uORB_publish_results().
| #define MAX_DETECTABLE_TEMPERATURE 100.0f |
Definition at line 60 of file pga460.h.
Referenced by PGA460::calculate_object_distance().
| #define MAX_SAMPLE_DEVIATION 0.15f |
Definition at line 64 of file pga460.h.
Referenced by PGA460::uORB_publish_results().
| #define MIN_DETECTABLE_DISTANCE 0.05f |
Definition at line 59 of file pga460.h.
Referenced by PGA460::uORB_publish_results().
| #define MIN_DETECTABLE_TEMPERATURE -20.0f |
Definition at line 61 of file pga460.h.
Referenced by PGA460::calculate_object_distance().
| #define MODE_LONG_RANGE P2BL |
Definition at line 70 of file pga460.h.
Referenced by PGA460::set_range_mode().
| #define MODE_SET_HYST 0.0f |
Definition at line 63 of file pga460.h.
Referenced by PGA460::set_range_mode().
| #define MODE_SET_THRESH 0.6f |
Definition at line 62 of file pga460.h.
Referenced by PGA460::set_range_mode().
| #define MODE_SHORT_RANGE P1BL |
Definition at line 69 of file pga460.h.
Referenced by PGA460::set_range_mode().
| #define NUM_SAMPLES_CONSISTENT 5 |
Definition at line 65 of file pga460.h.
Referenced by PGA460::uORB_publish_results().
| #define P1_GAIN_CTRL 0x0 |
Definition at line 153 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define P1_THR_0 0x54 |
Definition at line 176 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_1 0x5C |
Definition at line 177 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_10 0x5A |
Definition at line 186 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_11 0xFF |
Definition at line 187 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_12 0xFF |
Definition at line 188 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_13 0xFF |
Definition at line 189 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_14 0xFF |
Definition at line 190 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_15 0x0 |
Definition at line 191 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_2 0xBD |
Definition at line 178 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_3 0xE0 |
Definition at line 179 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_4 0x6 |
Definition at line 180 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_5 0xCF |
Definition at line 181 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_6 0xEE |
Definition at line 182 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_7 0x8E |
Definition at line 183 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_8 0x84 |
Definition at line 184 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P1_THR_9 0xB6 |
Definition at line 185 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_GAIN_CTRL 0x8 |
Definition at line 154 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define P2_THR_0 0xBA |
Definition at line 192 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_1 0xCF |
Definition at line 193 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_10 0xDF |
Definition at line 202 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_11 0xFF |
Definition at line 203 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_12 0xFF |
Definition at line 204 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_13 0xFF |
Definition at line 205 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_14 0xFF |
Definition at line 206 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_15 0x0 |
Definition at line 207 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_2 0xFF |
Definition at line 194 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_3 0xF5 |
Definition at line 195 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_4 0x1A |
Definition at line 196 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_5 0x5F |
Definition at line 197 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_6 0xFA |
Definition at line 198 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_7 0xD6 |
Definition at line 199 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_8 0xB6 |
Definition at line 200 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define P2_THR_9 0x35 |
Definition at line 201 of file pga460.h.
Referenced by PGA460::initialize_thresholds(), and PGA460::read_threshold_registers().
| #define PGA460_DEFAULT_PORT "/dev/ttyS6" |
Definition at line 57 of file pga460.h.
Referenced by PGA460::instantiate().
| #define POLL_RATE_US 0ULL |
Definition at line 67 of file pga460.h.
Referenced by PGA460::run().
| #define PULSE_P1 0x0C |
Definition at line 142 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define PULSE_P2 0x1F |
Definition at line 143 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define REC_LENGTH 0x44 |
Definition at line 146 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define SAT_FDIAG_TH 0x2C |
Definition at line 148 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define SRR 0x09 |
Definition at line 86 of file pga460.h.
Referenced by PGA460::read_register().
| #define SRW 0x0A |
Definition at line 87 of file pga460.h.
Referenced by PGA460::flash_eeprom(), PGA460::unlock_eeprom(), and PGA460::write_register().
| #define SYNCBYTE 0x55 |
Definition at line 72 of file pga460.h.
Referenced by PGA460::flash_eeprom(), PGA460::get_temperature(), PGA460::initialize_thresholds(), PGA460::read_eeprom(), PGA460::read_register(), PGA460::read_threshold_registers(), PGA460::request_results(), PGA460::take_measurement(), PGA460::unlock_eeprom(), PGA460::write_eeprom(), and PGA460::write_register().
| #define TEMP_TRIM 0x0 |
Definition at line 152 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define THRBR 0x0F |
Definition at line 92 of file pga460.h.
Referenced by PGA460::read_threshold_registers().
| #define TNLM 0x04 |
Definition at line 81 of file pga460.h.
Referenced by PGA460::get_temperature().
| #define TNLR 0x06 |
Definition at line 83 of file pga460.h.
Referenced by PGA460::get_temperature().
| #define TVGAIN0 0x9D |
Definition at line 132 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define TVGAIN1 0xBD |
Definition at line 133 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define TVGAIN2 0xEF |
Definition at line 134 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define TVGAIN3 0x31 |
Definition at line 135 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define TVGAIN4 0x48 |
Definition at line 136 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define TVGAIN5 0x67 |
Definition at line 137 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define TVGAIN6 0xAC |
Definition at line 138 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define UMR 0x05 |
Definition at line 82 of file pga460.h.
Referenced by PGA460::request_results().
| #define USER_DATA1 0xAA |
Definition at line 112 of file pga460.h.
Referenced by PGA460::initialize_device_settings(), PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA10 0x0 |
Definition at line 121 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA11 0x0 |
Definition at line 122 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA12 0x0 |
Definition at line 123 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA13 0x0 |
Definition at line 124 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA14 0x0 |
Definition at line 125 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA15 0x0 |
Definition at line 126 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA16 0x0 |
Definition at line 127 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA17 0x0 |
Definition at line 128 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA18 0x0 |
Definition at line 129 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA19 0x0 |
Definition at line 130 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA2 0x0 |
Definition at line 113 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA20 0x0 |
Definition at line 131 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA3 0x0 |
Definition at line 114 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA4 0x0 |
Definition at line 115 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA5 0x0 |
Definition at line 116 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA6 0x0 |
Definition at line 117 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA7 0x0 |
Definition at line 118 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA8 0x0 |
Definition at line 119 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().
| #define USER_DATA9 0x0 |
Definition at line 120 of file pga460.h.
Referenced by PGA460::read_eeprom(), and PGA460::write_eeprom().