|
PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <pga460.h>
Public Member Functions | |
| PGA460 (const char *port=PGA460_DEFAULT_PORT) | |
| virtual | ~PGA460 () |
| int | close_serial () |
| Closes the serial port. More... | |
| int | open_serial () |
| Opens the serial port. More... | |
| void | print_device_status () |
| Reports the diagnostic data from device status registers 1 and 2 if there is anything to report. More... | |
| void | print_diagnostics (const uint8_t diagnostic_byte) |
| Reports the diagnostic data the diagnostic byte (first byte from slave). More... | |
| int | print_status () override |
| Diagnostics - print some basic information about the driver. More... | |
| int | read_threshold_registers () |
| Reads the threshold registers. More... | |
| void | run () override |
| int | read_eeprom () |
| Reads the EEPROM and checks to see if it matches the default parameters. More... | |
| int | write_eeprom () |
| Writes the user defined paramaters to device EEPROM. More... | |
| uint8_t | read_register (const uint8_t reg) |
| Reads a register. More... | |
| int | write_register (const uint8_t reg, const uint8_t val) |
| Writes a value to a register. More... | |
Static Public Member Functions | |
| static int | custom_command (int argc, char *argv[]) |
| main Main entry point to the module that should be called directly from the module's main method. More... | |
| static PGA460 * | instantiate (int argc, char *argv[]) |
| Instantiates the pga460 object. More... | |
| static int | print_usage (const char *reason=nullptr) |
| Prints the module usage to the nuttshell console. More... | |
| static int | task_spawn (int argc, char *argv[]) |
Private Member Functions | |
| uint8_t | calc_checksum (uint8_t *data, const uint8_t size) |
| Calculates the checksum of the transmitted commmand + data. More... | |
| float | calculate_object_distance (uint16_t time_of_flight) |
| Calculates the distance from the measurement time of flight (time_of_flight) and current temperature. More... | |
| uint32_t | collect_results () |
| Collects the data in the serial port rx buffer, does math, and publishes the value to uORB. More... | |
| int | flash_eeprom () |
| Send the program command to the EEPROM to start the flash process. More... | |
| int | initialize_device_settings () |
| Writes program defined threshold defaults to the register map and checks/writes the EEPROM. More... | |
| int | initialize_thresholds () |
| Writes the user defined paramaters to device register map. More... | |
| int | request_results () |
| Measurement is read from UART RX buffer and published to the uORB distance sensor topic. More... | |
| uint8_t | set_range_mode () |
| Checks the measurement from last report and sets the range distance mode (long range , short range). More... | |
| int | take_measurement (const uint8_t mode) |
| Commands the device to perform an ultrasonic measurement. More... | |
| float | get_temperature () |
| int | unlock_eeprom () |
| Send the unlock command to the EEPROM to enable reading and writing – not needed w/ bulk write. More... | |
| void | uORB_publish_results (const float dist) |
| Commands the device to publish the measurement results to uORB. More... | |
Private Attributes | |
| orb_advert_t | _distance_sensor_topic {nullptr} |
| orb_advert_t uORB advertisement topic. More... | |
| int | _fd {-1} |
| char | _port [20] {} |
| float | _previous_report_distance {0} |
| float | _previous_valid_report_distance {0} |
| float | _resonant_frequency {41.0f} |
| uint8_t | _ranging_mode {MODE_SHORT_RANGE} |
| uint64_t | _start_loop {0} |
| PGA460::PGA460 | ( | const char * | port = PGA460_DEFAULT_PORT | ) |
Definition at line 44 of file pga460.cpp.
References _port.
Referenced by instantiate().
|
virtual |
Definition at line 52 of file pga460.cpp.
References _distance_sensor_topic, and orb_unadvertise().
|
private |
Calculates the checksum of the transmitted commmand + data.
| data | Pointer to the data a checksum will be calculated for. |
| size | The size of the data (bytes) the checksum will be calculated for. |
Definition at line 57 of file pga460.cpp.
References data.
Referenced by flash_eeprom(), get_temperature(), initialize_thresholds(), read_register(), take_measurement(), unlock_eeprom(), write_eeprom(), and write_register().
|
private |
Calculates the distance from the measurement time of flight (time_of_flight) and current temperature.
| time_of_flight | The reported time of flight in ms from the device. |
Definition at line 203 of file pga460.cpp.
References f(), get_temperature(), MAX_DETECTABLE_TEMPERATURE, and MIN_DETECTABLE_TEMPERATURE.
Referenced by collect_results().
| int PGA460::close_serial | ( | ) |
Closes the serial port.
Definition at line 85 of file pga460.cpp.
References _fd, and px4_close().
Referenced by run().
|
private |
Collects the data in the serial port rx buffer, does math, and publishes the value to uORB.
Definition at line 164 of file pga460.cpp.
References _fd, calculate_object_distance(), read(), and uORB_publish_results().
Referenced by run().
|
static |
main Main entry point to the module that should be called directly from the module's main method.
| argc | The input argument count. |
| argv | Pointer to the input argument array. |
Definition at line 96 of file pga460.cpp.
References print_usage().
|
private |
Send the program command to the EEPROM to start the flash process.
Definition at line 223 of file pga460.cpp.
References _fd, calc_checksum(), EE_CNTRL_ADDR, EE_UNLOCK_ST2, SRW, SYNCBYTE, and write().
Referenced by write_eeprom().
|
private |
Definition at line 238 of file pga460.cpp.
References _fd, calc_checksum(), f(), read(), SYNCBYTE, TNLM, TNLR, and write().
Referenced by calculate_object_distance().
|
private |
Writes program defined threshold defaults to the register map and checks/writes the EEPROM.
Definition at line 107 of file pga460.cpp.
References initialize_thresholds(), read_eeprom(), read_register(), USER_DATA1, and write_eeprom().
Referenced by run().
|
private |
Writes the user defined paramaters to device register map.
Definition at line 131 of file pga460.cpp.
References _fd, BC_THRBW, calc_checksum(), P1_THR_0, P1_THR_1, P1_THR_10, P1_THR_11, P1_THR_12, P1_THR_13, P1_THR_14, P1_THR_15, P1_THR_2, P1_THR_3, P1_THR_4, P1_THR_5, P1_THR_6, P1_THR_7, P1_THR_8, P1_THR_9, P2_THR_0, P2_THR_1, P2_THR_10, P2_THR_11, P2_THR_12, P2_THR_13, P2_THR_14, P2_THR_15, P2_THR_2, P2_THR_3, P2_THR_4, P2_THR_5, P2_THR_6, P2_THR_7, P2_THR_8, P2_THR_9, print_device_status(), read_threshold_registers(), SYNCBYTE, and write().
Referenced by initialize_device_settings().
|
static |
Instantiates the pga460 object.
| argc | The input argument count. |
| argv | Pointer to the input argument array. |
Definition at line 101 of file pga460.cpp.
References PGA460(), and PGA460_DEFAULT_PORT.
| int PGA460::open_serial | ( | ) |
Opens the serial port.
Definition at line 293 of file pga460.cpp.
References _fd, _port, and px4_open().
Referenced by run().
| void PGA460::print_device_status | ( | ) |
Reports the diagnostic data from device status registers 1 and 2 if there is anything to report.
Definition at line 360 of file pga460.cpp.
References read_register().
Referenced by initialize_thresholds().
| void PGA460::print_diagnostics | ( | const uint8_t | diagnostic_byte | ) |
Reports the diagnostic data the diagnostic byte (first byte from slave).
| diagnostic_byte | The diagnostic byte that contains the bitflags. |
Definition at line 412 of file pga460.cpp.
Referenced by read_eeprom(), read_register(), read_threshold_registers(), and write_eeprom().
|
override |
Diagnostics - print some basic information about the driver.
Definition at line 467 of file pga460.cpp.
References _previous_valid_report_distance.
|
static |
Prints the module usage to the nuttshell console.
| reason | The requested reason for printing to console. |
Definition at line 473 of file pga460.cpp.
Referenced by custom_command().
| int PGA460::read_eeprom | ( | ) |
Reads the EEPROM and checks to see if it matches the default parameters.
Definition at line 502 of file pga460.cpp.
References _fd, CURR_LIM_P1, CURR_LIM_P2, DEADTIME, DECPL_TEMP, DSP_SCALE, EEBR, FREQ_DIAG, FREQUENCY, FVOLT_DEC, INIT_GAIN, P1_GAIN_CTRL, P2_GAIN_CTRL, print_diagnostics(), PULSE_P1, PULSE_P2, read(), REC_LENGTH, SAT_FDIAG_TH, SYNCBYTE, TEMP_TRIM, TVGAIN0, TVGAIN1, TVGAIN2, TVGAIN3, TVGAIN4, TVGAIN5, TVGAIN6, unlock_eeprom(), USER_DATA1, USER_DATA10, USER_DATA11, USER_DATA12, USER_DATA13, USER_DATA14, USER_DATA15, USER_DATA16, USER_DATA17, USER_DATA18, USER_DATA19, USER_DATA2, USER_DATA20, USER_DATA3, USER_DATA4, USER_DATA5, USER_DATA6, USER_DATA7, USER_DATA8, USER_DATA9, and write().
Referenced by initialize_device_settings().
| uint8_t PGA460::read_register | ( | const uint8_t | reg | ) |
Reads a register.
| reg | The register to read from. |
Definition at line 563 of file pga460.cpp.
References _fd, calc_checksum(), print_diagnostics(), read(), SRR, SYNCBYTE, unlock_eeprom(), and write().
Referenced by initialize_device_settings(), print_device_status(), and write_eeprom().
| int PGA460::read_threshold_registers | ( | ) |
Reads the threshold registers.
Definition at line 609 of file pga460.cpp.
References _fd, P1_THR_0, P1_THR_1, P1_THR_10, P1_THR_11, P1_THR_12, P1_THR_13, P1_THR_14, P1_THR_15, P1_THR_2, P1_THR_3, P1_THR_4, P1_THR_5, P1_THR_6, P1_THR_7, P1_THR_8, P1_THR_9, P2_THR_0, P2_THR_1, P2_THR_10, P2_THR_11, P2_THR_12, P2_THR_13, P2_THR_14, P2_THR_15, P2_THR_2, P2_THR_3, P2_THR_4, P2_THR_5, P2_THR_6, P2_THR_7, P2_THR_8, P2_THR_9, print_diagnostics(), read(), SYNCBYTE, THRBR, and write().
Referenced by initialize_thresholds().
|
private |
|
override |
Definition at line 678 of file pga460.cpp.
References _distance_sensor_topic, _start_loop, close_serial(), collect_results(), hrt_absolute_time(), initialize_device_settings(), open_serial(), orb_advertise(), ORB_ID, POLL_RATE_US, request_results(), set_range_mode(), and take_measurement().
|
private |
Checks the measurement from last report and sets the range distance mode (long range , short range).
Definition at line 718 of file pga460.cpp.
References _previous_valid_report_distance, _ranging_mode, MODE_LONG_RANGE, MODE_SET_HYST, MODE_SET_THRESH, and MODE_SHORT_RANGE.
Referenced by run().
|
private |
Commands the device to perform an ultrasonic measurement.
Definition at line 732 of file pga460.cpp.
References _fd, calc_checksum(), SYNCBYTE, and write().
Referenced by run().
|
static |
Definition at line 748 of file pga460.cpp.
|
private |
Send the unlock command to the EEPROM to enable reading and writing – not needed w/ bulk write.
Definition at line 819 of file pga460.cpp.
References _fd, calc_checksum(), EE_CNTRL_ADDR, EE_UNLOCK_ST1, SRW, SYNCBYTE, and write().
Referenced by read_eeprom(), read_register(), write_eeprom(), and write_register().
|
private |
Commands the device to publish the measurement results to uORB.
| dist | The calculated distance to the object. |
Definition at line 767 of file pga460.cpp.
References _distance_sensor_topic, _previous_report_distance, _previous_valid_report_distance, distance_sensor_s::current_distance, hrt_absolute_time(), MAX_DETECTABLE_DISTANCE, distance_sensor_s::max_distance, MAX_SAMPLE_DEVIATION, MIN_DETECTABLE_DISTANCE, distance_sensor_s::min_distance, NUM_SAMPLES_CONSISTENT, ORB_ID, orb_publish(), distance_sensor_s::orientation, distance_sensor_s::signal_quality, distance_sensor_s::timestamp, and distance_sensor_s::type.
Referenced by collect_results().
| int PGA460::write_eeprom | ( | ) |
Writes the user defined paramaters to device EEPROM.
Definition at line 835 of file pga460.cpp.
References _fd, calc_checksum(), CURR_LIM_P1, CURR_LIM_P2, DEADTIME, DECPL_TEMP, DSP_SCALE, EE_CNTRL_ADDR, EEBW, flash_eeprom(), FREQ_DIAG, FREQUENCY, FVOLT_DEC, INIT_GAIN, P1_GAIN_CTRL, P2_GAIN_CTRL, print_diagnostics(), PULSE_P1, PULSE_P2, read_register(), REC_LENGTH, SAT_FDIAG_TH, SYNCBYTE, TEMP_TRIM, TVGAIN0, TVGAIN1, TVGAIN2, TVGAIN3, TVGAIN4, TVGAIN5, TVGAIN6, unlock_eeprom(), USER_DATA1, USER_DATA10, USER_DATA11, USER_DATA12, USER_DATA13, USER_DATA14, USER_DATA15, USER_DATA16, USER_DATA17, USER_DATA18, USER_DATA19, USER_DATA2, USER_DATA20, USER_DATA3, USER_DATA4, USER_DATA5, USER_DATA6, USER_DATA7, USER_DATA8, USER_DATA9, and write().
Referenced by initialize_device_settings().
| int PGA460::write_register | ( | const uint8_t | reg, |
| const uint8_t | val | ||
| ) |
Writes a value to a register.
| reg | The register address to write to. |
| val | The value to write. |
Definition at line 879 of file pga460.cpp.
References _fd, calc_checksum(), SRW, SYNCBYTE, unlock_eeprom(), and write().
|
private |
|
private |
| _fd | Returns the file descriptor from px4_open(). |
Definition at line 391 of file pga460.h.
Referenced by close_serial(), collect_results(), flash_eeprom(), get_temperature(), initialize_thresholds(), open_serial(), read_eeprom(), read_register(), read_threshold_registers(), request_results(), take_measurement(), unlock_eeprom(), write_eeprom(), and write_register().
|
private |
| _port | Stores the port name. |
Definition at line 394 of file pga460.h.
Referenced by open_serial(), and PGA460().
|
private |
| _previous_report_distance | The previous reported sensor distance. |
Definition at line 397 of file pga460.h.
Referenced by uORB_publish_results().
|
private |
| _previous_valid_report_distance | The previous valid reported sensor distance. |
Definition at line 400 of file pga460.h.
Referenced by print_status(), set_range_mode(), and uORB_publish_results().
|
private |
| _mode_long_range | Flag for long range mode. If false, sensor is in short range mode. |
Definition at line 406 of file pga460.h.
Referenced by set_range_mode().
|
private |
|
private |