|
PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Public Member Functions | |
| LeddarOne (const char *device_path, const char *serial_port=LEDDAR_ONE_DEFAULT_SERIAL_PORT, const uint8_t device_orientation=distance_sensor_s::ROTATION_DOWNWARD_FACING) | |
| virtual | ~LeddarOne () |
| virtual int | init () override |
| void | print_info () |
| Diagnostics - print some basic information about the driver. More... | |
| void | start () |
| Initialise the automatic measurement state machine and start it. More... | |
| void | stop () |
| Stop the automatic measurement state machine. More... | |
Public Member Functions inherited from cdev::CDev | |
| CDev (const char *devname) | |
| Constructor. More... | |
| CDev (const CDev &)=delete | |
| CDev & | operator= (const CDev &)=delete |
| CDev (CDev &&)=delete | |
| CDev & | operator= (CDev &&)=delete |
| virtual | ~CDev () |
| virtual int | open (file_t *filep) |
| Handle an open of the device. More... | |
| virtual int | close (file_t *filep) |
| Handle a close of the device. More... | |
| virtual ssize_t | read (file_t *filep, char *buffer, size_t buflen) |
| Perform a read from the device. More... | |
| virtual ssize_t | write (file_t *filep, const char *buffer, size_t buflen) |
| Perform a write to the device. More... | |
| virtual off_t | seek (file_t *filep, off_t offset, int whence) |
| Perform a logical seek operation on the device. More... | |
| virtual int | ioctl (file_t *filep, int cmd, unsigned long arg) |
| Perform an ioctl operation on the device. More... | |
| virtual int | poll (file_t *filep, px4_pollfd_struct_t *fds, bool setup) |
| Perform a poll setup/teardown operation. More... | |
| const char * | get_devname () const |
| Get the device name. More... | |
Private Member Functions | |
| uint16_t | crc16_calc (const unsigned char *data_frame, const uint8_t crc16_length) |
| Calculates the 16 byte crc value for the data frame. More... | |
| int | collect () |
| Reads the data measrurement from serial UART. More... | |
| int | measure () |
| Sends a data request message to the sensor. More... | |
| int | open_serial_port (const speed_t speed=B115200) |
| Opens and configures the UART serial communications port. More... | |
| void | Run () override |
Private Attributes | |
| const char * | _serial_port {nullptr} |
| PX4Rangefinder | _px4_rangefinder |
| int | _file_descriptor {-1} |
| int | _orb_class_instance {-1} |
| uint8_t | _buffer [sizeof(reading_msg)] |
| uint8_t | _buffer_len {0} |
| hrt_abstime | _measurement_time {0} |
| perf_counter_t | _comms_error {perf_alloc(PC_COUNT, "leddar_one_comms_error")} |
| perf_counter_t | _sample_perf {perf_alloc(PC_ELAPSED, "leddar_one_sample")} |
Additional Inherited Members | |
Protected Member Functions inherited from cdev::CDev | |
| virtual pollevent_t | poll_state (file_t *filep) |
| Check the current state of the device for poll events from the perspective of the file. More... | |
| virtual void | poll_notify (pollevent_t events) |
| Report new poll events. More... | |
| virtual void | poll_notify_one (px4_pollfd_struct_t *fds, pollevent_t events) |
| Internal implementation of poll_notify. More... | |
| virtual int | open_first (file_t *filep) |
| Notification of the first open. More... | |
| virtual int | close_last (file_t *filep) |
| Notification of the last close. More... | |
| virtual int | register_class_devname (const char *class_devname) |
| Register a class device name, automatically adding device class instance suffix if need be. More... | |
| virtual int | unregister_class_devname (const char *class_devname, unsigned class_instance) |
| Register a class device name, automatically adding device class instance suffix if need be. More... | |
| void | lock () |
| Take the driver lock. More... | |
| void | unlock () |
| Release the driver lock. More... | |
| int | unregister_driver_and_memory () |
| First, unregisters the driver. More... | |
Protected Attributes inherited from cdev::CDev | |
| px4_sem_t | _lock |
| lock to protect access to all class members (also for derived classes) More... | |
Static Protected Attributes inherited from cdev::CDev | |
| static const px4_file_operations_t | fops = {} |
| Pointer to the default cdev file operations table; useful for registering clone devices etc. More... | |
Definition at line 107 of file leddar_one.cpp.
| LeddarOne::LeddarOne | ( | const char * | device_path, |
| const char * | serial_port = LEDDAR_ONE_DEFAULT_SERIAL_PORT, |
||
| const uint8_t | device_orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING |
||
| ) |
Definition at line 175 of file leddar_one.cpp.
References _px4_rangefinder, _serial_port, LEDDAR_ONE_FIELD_OF_VIEW, LEDDAR_ONE_MAX_DISTANCE, LEDDAR_ONE_MIN_DISTANCE, PX4Rangefinder::set_device_type(), PX4Rangefinder::set_fov(), PX4Rangefinder::set_max_distance(), PX4Rangefinder::set_min_distance(), and PX4Rangefinder::set_orientation().
Referenced by leddar_one::start().
|
virtual |
Definition at line 189 of file leddar_one.cpp.
References _comms_error, _sample_perf, _serial_port, perf_free(), and stop().
|
private |
Reads the data measrurement from serial UART.
Definition at line 219 of file leddar_one.cpp.
References _buffer, _buffer_len, _comms_error, _file_descriptor, _measurement_time, _px4_rangefinder, _sample_perf, crc16(), crc16_calc(), f(), measure(), MODBUS_READING_FUNCTION, MODBUS_SLAVE_ADDRESS, msg, perf_begin(), perf_count(), perf_end(), cdev::CDev::read(), and PX4Rangefinder::update().
Referenced by init(), and Run().
|
private |
Calculates the 16 byte crc value for the data frame.
| data_frame | The data frame to compute a checksum for. |
| crc16_length | The length of the data frame. |
Definition at line 198 of file leddar_one.cpp.
Referenced by collect().
|
overridevirtual |
Reimplemented from cdev::CDev.
Definition at line 276 of file leddar_one.cpp.
References collect(), hrt_absolute_time(), hrt_abstime, ToneAlarmInterface::init(), LEDDAR_ONE_MEASURE_INTERVAL, measure(), open_serial_port(), and stop().
Referenced by leddar_one::start().
|
private |
Sends a data request message to the sensor.
Definition at line 312 of file leddar_one.cpp.
References _buffer_len, _file_descriptor, _measurement_time, hrt_absolute_time(), request_reading_msg, and cdev::CDev::write().
Referenced by collect(), and init().
|
private |
Opens and configures the UART serial communications port.
| speed | The baudrate (speed) to configure the serial UART port. |
Definition at line 330 of file leddar_one.cpp.
References _file_descriptor, _serial_port, cdev::CDev::close(), and cdev::CDev::open().
Referenced by init(), and Run().
| void LeddarOne::print_info | ( | ) |
Diagnostics - print some basic information about the driver.
Definition at line 406 of file leddar_one.cpp.
References _comms_error, _sample_perf, LEDDAR_ONE_MEASURE_INTERVAL, and perf_print_counter().
Referenced by leddar_one::status().
|
overrideprivate |
Definition at line 414 of file leddar_one.cpp.
References collect(), and open_serial_port().
| void LeddarOne::start | ( | ) |
Initialise the automatic measurement state machine and start it.
Definition at line 423 of file leddar_one.cpp.
References LEDDAR_ONE_MEASURE_INTERVAL.
Referenced by leddar_one::start().
| void LeddarOne::stop | ( | ) |
Stop the automatic measurement state machine.
Definition at line 431 of file leddar_one.cpp.
References _file_descriptor, and cdev::CDev::close().
Referenced by init(), and ~LeddarOne().
|
private |
Definition at line 166 of file leddar_one.cpp.
Referenced by collect().
|
private |
Definition at line 167 of file leddar_one.cpp.
|
private |
Definition at line 171 of file leddar_one.cpp.
Referenced by collect(), print_info(), and ~LeddarOne().
|
private |
Definition at line 163 of file leddar_one.cpp.
Referenced by collect(), measure(), open_serial_port(), and stop().
|
private |
Definition at line 169 of file leddar_one.cpp.
|
private |
Definition at line 164 of file leddar_one.cpp.
|
private |
Definition at line 161 of file leddar_one.cpp.
Referenced by collect(), and LeddarOne().
|
private |
Definition at line 172 of file leddar_one.cpp.
Referenced by collect(), print_info(), and ~LeddarOne().
|
private |
Definition at line 159 of file leddar_one.cpp.
Referenced by LeddarOne(), open_serial_port(), and ~LeddarOne().