| 
    PX4 Firmware
    
   PX4 Autopilot Software http://px4.io 
   | 
 
Public Member Functions | |
| Radar (const char *port=RADAR_DEFAULT_PORT, uint8_t rotation=distance_sensor_s::ROTATION_DOWNWARD_FACING) | |
| Default Constructor.  More... | |
| virtual | ~Radar () | 
| Virtual destructor.  More... | |
| virtual int | init () override | 
| Method : init() This method initializes the general driver for a range finder sensor.  More... | |
| void | print_info () | 
| Diagnostics - print some basic information about the driver.  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 | |
| int | collect () | 
| Reads data from serial UART and places it into a buffer.  More... | |
| int | open_serial_port (const speed_t speed=B115200) | 
| Opens and configures the UART serial communications port.  More... | |
| void | Run () override | 
| Perform a reading cycle; collect from the previous measurement and start a new one.  More... | |
| void | start () | 
| Initialise the automatic measurement state machine and start it.  More... | |
| void | stop () | 
| Stops the automatic measurement state machine.  More... | |
Private Attributes | |
| char | _port [20] | 
| int | _file_descriptor {-1} | 
| int | _orb_class_instance {-1} | 
| unsigned int | _head {0} | 
| unsigned int | _tail {0} | 
| uint8_t | _buffer [ULANDING_BUFFER_LENGTH] {} | 
| uint8_t | _rotation | 
| perf_counter_t | _comms_errors {perf_alloc(PC_COUNT, "radar_com_err")} | 
| perf_counter_t | _sample_perf {perf_alloc(PC_ELAPSED, "radar_read")} | 
| orb_advert_t | _distance_sensor_topic {nullptr} | 
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 101 of file ulanding.cpp.
| Radar::Radar | ( | const char * | port = RADAR_DEFAULT_PORT,  | 
        
| uint8_t | rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING  | 
        ||
| ) | 
Default Constructor.
| port | The serial port to open for communicating with the sensor. | 
| rotation | The sensor rotation relative to the vehicle body. | 
Definition at line 173 of file ulanding.cpp.
References _port.
Referenced by radar::start().
      
  | 
  virtual | 
Virtual destructor.
Definition at line 184 of file ulanding.cpp.
References _comms_errors, _sample_perf, perf_free(), and stop().
      
  | 
  private | 
Reads data from serial UART and places it into a buffer.
Definition at line 194 of file ulanding.cpp.
References _buffer, _distance_sensor_topic, _file_descriptor, _rotation, _sample_perf, math::constrain(), distance_sensor_s::current_distance, f(), hrt_absolute_time(), distance_sensor_s::id, distance_sensor_s::max_distance, distance_sensor_s::min_distance, ORB_ID, orb_publish(), distance_sensor_s::orientation, perf_begin(), perf_end(), cdev::CDev::poll_notify(), cdev::CDev::read(), SENS_VARIANCE, distance_sensor_s::signal_quality, distance_sensor_s::timestamp, distance_sensor_s::type, ULANDING_MAX_DISTANCE, ULANDING_MIN_DISTANCE, ULANDING_PACKET_HDR, ULANDING_VERSION, and distance_sensor_s::variance.
Referenced by Run().
      
  | 
  overridevirtual | 
Method : init() This method initializes the general driver for a range finder sensor.
Reimplemented from cdev::CDev.
Definition at line 271 of file ulanding.cpp.
References _distance_sensor_topic, _orb_class_instance, ToneAlarmInterface::init(), OK, orb_advertise_multi(), ORB_ID, ORB_PRIO_HIGH, and start().
Referenced by radar::start().
      
  | 
  private | 
Opens and configures the UART serial communications port.
| speed | The baudrate (speed) to configure the serial UART port. | 
Definition at line 292 of file ulanding.cpp.
References _file_descriptor, _port, cdev::CDev::close(), and cdev::CDev::open().
Referenced by Run().
| void Radar::print_info | ( | ) | 
Diagnostics - print some basic information about the driver.
Definition at line 364 of file ulanding.cpp.
References _comms_errors, _sample_perf, perf_print_counter(), ULANDING_MAX_DISTANCE, ULANDING_MEASURE_INTERVAL, and ULANDING_MIN_DISTANCE.
Referenced by radar::status().
      
  | 
  overrideprivate | 
Perform a reading cycle; collect from the previous measurement and start a new one.
Definition at line 374 of file ulanding.cpp.
References collect(), and open_serial_port().
      
  | 
  private | 
Initialise the automatic measurement state machine and start it.
Definition at line 383 of file ulanding.cpp.
References ULANDING_MEASURE_INTERVAL.
Referenced by init(), and radar::reset().
      
  | 
  private | 
Stops the automatic measurement state machine.
Definition at line 391 of file ulanding.cpp.
References _file_descriptor, and cdev::CDev::close().
Referenced by radar::reset(), and ~Radar().
      
  | 
  private | 
Definition at line 164 of file ulanding.cpp.
Referenced by collect().
      
  | 
  private | 
Definition at line 167 of file ulanding.cpp.
Referenced by print_info(), and ~Radar().
      
  | 
  private | 
Definition at line 170 of file ulanding.cpp.
      
  | 
  private | 
Definition at line 158 of file ulanding.cpp.
Referenced by collect(), open_serial_port(), and stop().
      
  | 
  private | 
Definition at line 161 of file ulanding.cpp.
      
  | 
  private | 
Definition at line 159 of file ulanding.cpp.
Referenced by init().
      
  | 
  private | 
Definition at line 156 of file ulanding.cpp.
Referenced by open_serial_port(), and Radar().
      
  | 
  private | 
Definition at line 165 of file ulanding.cpp.
Referenced by collect().
      
  | 
  private | 
Definition at line 168 of file ulanding.cpp.
Referenced by collect(), print_info(), and ~Radar().
      
  | 
  private | 
Definition at line 162 of file ulanding.cpp.