#include <urg_c_wrapper.h>
|  | 
| ros::Duration | computeLatency (size_t num_measurements) | 
|  | 
| double | getAngleIncrement () const | 
|  | 
| double | getAngleMax () const | 
|  | 
| double | getAngleMaxLimit () const | 
|  | 
| double | getAngleMin () const | 
|  | 
| double | getAngleMinLimit () const | 
|  | 
| bool | getAR00Status (URGStatus &status) | 
|  | 
| ros::Duration | getComputedLatency () const | 
|  | 
| std::string | getDeviceID () | 
|  | 
| bool | getDL00Status (UrgDetectionReport &report) | 
|  | 
| std::string | getFirmwareDate () | 
|  | 
| std::string | getFirmwareVersion () | 
|  | 
| std::string | getIPAddress () const | 
|  | 
| int | getIPPort () const | 
|  | 
| std::string | getProductName () | 
|  | 
| std::string | getProtocolVersion () | 
|  | 
| double | getRangeMax () const | 
|  | 
| double | getRangeMin () const | 
|  | 
| double | getScanPeriod () const | 
|  | 
| std::string | getSensorState () | 
|  | 
| std::string | getSensorStatus () | 
|  | 
| int | getSerialBaud () const | 
|  | 
| std::string | getSerialPort () const | 
|  | 
| double | getTimeIncrement () const | 
|  | 
| ros::Duration | getUserTimeOffset () const | 
|  | 
| std::string | getVendorName () | 
|  | 
| bool | grabScan (const sensor_msgs::LaserScanPtr &msg) | 
|  | 
| bool | grabScan (const sensor_msgs::MultiEchoLaserScanPtr &msg) | 
|  | 
| bool | isStarted () const | 
|  | 
| bool | setAngleLimitsAndCluster (double &angle_min, double &angle_max, int cluster) | 
|  | 
| void | setFrameId (const std::string &frame_id) | 
|  | 
| void | setSkip (int skip) | 
|  | 
| void | setUserLatency (const double latency) | 
|  | 
| void | start () | 
|  | 
| void | stop () | 
|  | 
|  | URGCWrapper (const std::string &ip_address, const int ip_port, bool &using_intensity, bool &using_multiecho, bool synchronize_time) | 
|  | 
|  | URGCWrapper (const int serial_baud, const std::string &serial_port, bool &using_intensity, bool &using_multiecho, bool synchronize_time) | 
|  | 
|  | ~URGCWrapper () | 
|  | 
Definition at line 89 of file urg_c_wrapper.h.
 
      
        
          | urg_node::URGCWrapper::URGCWrapper | ( | const std::string & | ip_address, | 
        
          |  |  | const int | ip_port, | 
        
          |  |  | bool & | using_intensity, | 
        
          |  |  | bool & | using_multiecho, | 
        
          |  |  | bool | synchronize_time | 
        
          |  | ) |  |  | 
      
 
 
      
        
          | urg_node::URGCWrapper::URGCWrapper | ( | const int | serial_baud, | 
        
          |  |  | const std::string & | serial_port, | 
        
          |  |  | bool & | using_intensity, | 
        
          |  |  | bool & | using_multiecho, | 
        
          |  |  | bool | synchronize_time | 
        
          |  | ) |  |  | 
      
 
 
      
        
          | urg_node::URGCWrapper::~URGCWrapper | ( |  | ) |  | 
      
 
 
  
  | 
        
          | uint16_t urg_node::URGCWrapper::checkCRC | ( | const char * | bytes, |  
          |  |  | const uint32_t | size |  
          |  | ) |  |  |  | private | 
 
calculate the crc of a given set of bytes. 
- Parameters
- 
  
    | bytes | The bytes array to be processed. |  | size | The size of the bytes array. |  
 
- Returns
- the calculated CRC of the bytes. 
Definition at line 572 of file urg_c_wrapper.cpp.
 
 
      
        
          | ros::Duration urg_node::URGCWrapper::computeLatency | ( | size_t | num_measurements | ) |  | 
      
 
 
      
        
          | double urg_node::URGCWrapper::getAngleIncrement | ( |  | ) | const | 
      
 
 
      
        
          | double urg_node::URGCWrapper::getAngleMax | ( |  | ) | const | 
      
 
 
      
        
          | double urg_node::URGCWrapper::getAngleMaxLimit | ( |  | ) | const | 
      
 
 
      
        
          | double urg_node::URGCWrapper::getAngleMin | ( |  | ) | const | 
      
 
 
      
        
          | double urg_node::URGCWrapper::getAngleMinLimit | ( |  | ) | const | 
      
 
 
  
  | 
        
          | ros::Duration urg_node::URGCWrapper::getAngularTimeOffset | ( |  | ) | const |  | private | 
 
 
      
        
          | bool urg_node::URGCWrapper::getAR00Status | ( | URGStatus & | status | ) |  | 
      
 
 
      
        
          | ros::Duration urg_node::URGCWrapper::getComputedLatency | ( |  | ) | const | 
      
 
 
      
        
          | std::string urg_node::URGCWrapper::getDeviceID | ( |  | ) |  | 
      
 
 
      
        
          | std::string urg_node::URGCWrapper::getFirmwareDate | ( |  | ) |  | 
      
 
 
      
        
          | std::string urg_node::URGCWrapper::getFirmwareVersion | ( |  | ) |  | 
      
 
 
      
        
          | std::string urg_node::URGCWrapper::getIPAddress | ( |  | ) | const | 
      
 
 
      
        
          | int urg_node::URGCWrapper::getIPPort | ( |  | ) | const | 
      
 
 
  
  | 
        
          | ros::Duration urg_node::URGCWrapper::getNativeClockOffset | ( | size_t | num_measurements | ) |  |  | private | 
 
 
      
        
          | std::string urg_node::URGCWrapper::getProductName | ( |  | ) |  | 
      
 
 
      
        
          | std::string urg_node::URGCWrapper::getProtocolVersion | ( |  | ) |  | 
      
 
 
      
        
          | double urg_node::URGCWrapper::getRangeMax | ( |  | ) | const | 
      
 
 
      
        
          | double urg_node::URGCWrapper::getRangeMin | ( |  | ) | const | 
      
 
 
      
        
          | double urg_node::URGCWrapper::getScanPeriod | ( |  | ) | const | 
      
 
 
      
        
          | std::string urg_node::URGCWrapper::getSensorState | ( |  | ) |  | 
      
 
 
      
        
          | std::string urg_node::URGCWrapper::getSensorStatus | ( |  | ) |  | 
      
 
 
      
        
          | int urg_node::URGCWrapper::getSerialBaud | ( |  | ) | const | 
      
 
 
      
        
          | std::string urg_node::URGCWrapper::getSerialPort | ( |  | ) | const | 
      
 
 
  
  | 
        
          | ros::Time urg_node::URGCWrapper::getSynchronizedTime | ( | long | time_stamp, |  
          |  |  | long long | system_time_stamp |  
          |  | ) |  |  |  | private | 
 
Get synchronized time stamp using hardware clock. 
- Parameters
- 
  
    | time_stamp | The current hardware time stamp. |  | system_time_stamp | The current system time stamp. |  
 
- Returns
- ros::Time stamp representing synchronized time 
Definition at line 1052 of file urg_c_wrapper.cpp.
 
 
      
        
          | double urg_node::URGCWrapper::getTimeIncrement | ( |  | ) | const | 
      
 
 
  
  | 
        
          | ros::Duration urg_node::URGCWrapper::getTimeStampOffset | ( | size_t | num_measurements | ) |  |  | private | 
 
 
      
        
          | std::string urg_node::URGCWrapper::getVendorName | ( |  | ) |  | 
      
 
 
      
        
          | bool urg_node::URGCWrapper::grabScan | ( | const sensor_msgs::LaserScanPtr & | msg | ) |  | 
      
 
 
      
        
          | bool urg_node::URGCWrapper::grabScan | ( | const sensor_msgs::MultiEchoLaserScanPtr & | msg | ) |  | 
      
 
 
  
  | 
        
          | void urg_node::URGCWrapper::initialize | ( | bool & | using_intensity, |  
          |  |  | bool & | using_multiecho, |  
          |  |  | bool | synchronize_time |  
          |  | ) |  |  |  | private | 
 
 
  
  | 
        
          | bool urg_node::URGCWrapper::isIntensitySupported | ( |  | ) |  |  | private | 
 
 
  
  | 
        
          | bool urg_node::URGCWrapper::isMultiEchoSupported | ( |  | ) |  |  | private | 
 
 
      
        
          | bool urg_node::URGCWrapper::isStarted | ( |  | ) | const | 
      
 
 
  
  | 
        
          | std::string urg_node::URGCWrapper::sendCommand | ( | std::string | cmd | ) |  |  | private | 
 
Send an arbitrary serial command to the lidar. These commands can also be sent via the ethernet socket. 
- Parameters
- 
  
    | cmd | The arbitrary command fully formatted to be sent as provided |  
 
- Returns
- The textual response of the Lidar, empty if, but may return lidar's own error string. 
Definition at line 579 of file urg_c_wrapper.cpp.
 
 
      
        
          | bool urg_node::URGCWrapper::setAngleLimitsAndCluster | ( | double & | angle_min, | 
        
          |  |  | double & | angle_max, | 
        
          |  |  | int | cluster | 
        
          |  | ) |  |  | 
      
 
 
      
        
          | void urg_node::URGCWrapper::setFrameId | ( | const std::string & | frame_id | ) |  | 
      
 
 
      
        
          | void urg_node::URGCWrapper::setSkip | ( | int | skip | ) |  | 
      
 
 
  
  | 
        
          | bool urg_node::URGCWrapper::setToSCIP2 | ( |  | ) |  |  | private | 
 
Set the Hokuyo URG-04LX from SCIP 1.1 mode to SCIP 2.0 mode. 
- Returns
- True if successful and false if not. 
Definition at line 545 of file urg_c_wrapper.cpp.
 
 
      
        
          | void urg_node::URGCWrapper::setUserLatency | ( | const double | latency | ) |  | 
      
 
 
      
        
          | void urg_node::URGCWrapper::start | ( |  | ) |  | 
      
 
 
      
        
          | void urg_node::URGCWrapper::stop | ( |  | ) |  | 
      
 
 
  
  | 
        
          | const double urg_node::URGCWrapper::adj_alpha_ = .01 |  | private | 
 
 
  
  | 
        
          | uint64_t urg_node::URGCWrapper::adj_count_ |  | private | 
 
 
  
  | 
        
          | int urg_node::URGCWrapper::cluster_ |  | private | 
 
 
  
  | 
        
          | std::vector<long> urg_node::URGCWrapper::data_ |  | private | 
 
 
  
  | 
        
          | int urg_node::URGCWrapper::first_step_ |  | private | 
 
 
  
  | 
        
          | std::string urg_node::URGCWrapper::frame_id_ |  | private | 
 
 
  
  | 
        
          | double urg_node::URGCWrapper::hardware_clock_ |  | private | 
 
 
  
  | 
        
          | double urg_node::URGCWrapper::hardware_clock_adj_ |  | private | 
 
 
  
  | 
        
          | std::vector<unsigned short> urg_node::URGCWrapper::intensity_ |  | private | 
 
 
  
  | 
        
          | std::string urg_node::URGCWrapper::ip_address_ |  | private | 
 
 
  
  | 
        
          | int urg_node::URGCWrapper::ip_port_ |  | private | 
 
 
  
  | 
        
          | long urg_node::URGCWrapper::last_hardware_time_stamp_ |  | private | 
 
 
  
  | 
        
          | int urg_node::URGCWrapper::last_step_ |  | private | 
 
 
  
  | 
        
          | int urg_node::URGCWrapper::serial_baud_ |  | private | 
 
 
  
  | 
        
          | std::string urg_node::URGCWrapper::serial_port_ |  | private | 
 
 
  
  | 
        
          | int urg_node::URGCWrapper::skip_ |  | private | 
 
 
  
  | 
        
          | bool urg_node::URGCWrapper::started_ |  | private | 
 
 
  
  | 
        
          | bool urg_node::URGCWrapper::synchronize_time_ |  | private | 
 
 
  
  | 
        
          | urg_t urg_node::URGCWrapper::urg_ |  | private | 
 
 
  
  | 
        
          | bool urg_node::URGCWrapper::use_intensity_ |  | private | 
 
 
  
  | 
        
          | bool urg_node::URGCWrapper::use_multiecho_ |  | private | 
 
 
The documentation for this class was generated from the following files: