34 #ifndef URG_NODE_URG_C_WRAPPER_H    35 #define URG_NODE_URG_C_WRAPPER_H    42 #include <sensor_msgs/LaserScan.h>    43 #include <sensor_msgs/MultiEchoLaserScan.h>    92   URGCWrapper(
const std::string& ip_address, 
const int ip_port,
    93       bool& using_intensity, 
bool& using_multiecho, 
bool synchronize_time);
    95   URGCWrapper(
const int serial_baud, 
const std::string& serial_port,
    96       bool& using_intensity, 
bool& using_multiecho, 
bool synchronize_time);
   104   bool isStarted() 
const;
   106   double getRangeMin() 
const;
   108   double getRangeMax() 
const;
   110   double getAngleMin() 
const;
   112   double getAngleMax() 
const;
   114   double getAngleMinLimit() 
const;
   116   double getAngleMaxLimit() 
const;
   118   double getAngleIncrement() 
const;
   120   double getScanPeriod() 
const;
   122   double getTimeIncrement() 
const;
   124   std::string getIPAddress() 
const;
   126   int getIPPort() 
const;
   128   std::string getSerialPort() 
const;
   130   int getSerialBaud() 
const;
   132   std::string getVendorName();
   134   std::string getProductName();
   136   std::string getFirmwareVersion();
   138   std::string getFirmwareDate();
   140   std::string getProtocolVersion();
   142   std::string getDeviceID();
   148   std::string getSensorStatus();
   150   std::string getSensorState();
   152   void setFrameId(
const std::string& frame_id);
   154   void setUserLatency(
const double latency);
   156   bool setAngleLimitsAndCluster(
double& angle_min, 
double& angle_max, 
int cluster);
   158   bool setSkip(
int skip);
   162   bool grabScan(
const sensor_msgs::LaserScanPtr& 
msg);
   164   bool grabScan(
const sensor_msgs::MultiEchoLaserScanPtr& msg);
   171   void initialize(
bool& using_intensity, 
bool& using_multiecho, 
bool synchronize_time);
   173   bool isIntensitySupported();
   175   bool isMultiEchoSupported();
   189   ros::Time getSynchronizedTime(
long time_stamp, 
long long system_time_stamp);
   203   uint16_t checkCRC(
const char* bytes, 
const uint32_t size);
   211   std::string sendCommand(std::string 
cmd);
   237   const double adj_alpha_ = .01;
   247 #endif  // URG_NODE_URG_C_WRAPPER_H 
double hardware_clock_adj_
ros::Duration user_latency_
ROSCONSOLE_DECL void initialize()
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const 
urg_measurement_type_t measurement_type_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
std::vector< unsigned short > intensity_
long last_hardware_time_stamp_
std::vector< long > data_
ros::Duration system_latency_
std::string frame_id_
Output frame_id for each laserscan.