Public Member Functions | Private Member Functions | Private Attributes
urg_node::URGCWrapper Class Reference

#include <urg_c_wrapper.h>

List of all members.

Public Member Functions

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)
bool 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 ()

Private Member Functions

uint16_t checkCRC (const char *bytes, const uint32_t size)
 calculate the crc of a given set of bytes.
ros::Duration getAngularTimeOffset () const
ros::Duration getNativeClockOffset (size_t num_measurements)
ros::Time getSynchronizedTime (long time_stamp, long long system_time_stamp)
 Get synchronized time stamp using hardware clock.
ros::Duration getTimeStampOffset (size_t num_measurements)
void initialize (bool &using_intensity, bool &using_multiecho, bool synchronize_time)
bool isIntensitySupported ()
bool isMultiEchoSupported ()
std::string sendCommand (std::string cmd)
 Send an arbitrary serial command to the lidar. These commands can also be sent via the ethernet socket.
bool setToSCIP2 ()
 Set the Hokuyo URG-04LX from SCIP 1.1 mode to SCIP 2.0 mode.

Private Attributes

const double adj_alpha_ = .01
uint64_t adj_count_
int cluster_
std::vector< long > data_
int first_step_
std::string frame_id_
 Output frame_id for each laserscan.
double hardware_clock_
double hardware_clock_adj_
std::vector< unsigned short > intensity_
std::string ip_address_
int ip_port_
long last_hardware_time_stamp_
int last_step_
urg_measurement_type_t measurement_type_
int serial_baud_
std::string serial_port_
int skip_
bool started_
bool synchronize_time_
ros::Duration system_latency_
urg_t urg_
bool use_intensity_
bool use_multiecho_
ros::Duration user_latency_

Detailed Description

Definition at line 89 of file urg_c_wrapper.h.


Constructor & Destructor Documentation

urg_node::URGCWrapper::URGCWrapper ( const std::string &  ip_address,
const int  ip_port,
bool &  using_intensity,
bool &  using_multiecho,
bool  synchronize_time 
)

Definition at line 44 of file urg_c_wrapper.cpp.

urg_node::URGCWrapper::URGCWrapper ( const int  serial_baud,
const std::string &  serial_port,
bool &  using_intensity,
bool &  using_multiecho,
bool  synchronize_time 
)

Definition at line 70 of file urg_c_wrapper.cpp.

Definition at line 200 of file urg_c_wrapper.cpp.


Member Function Documentation

uint16_t urg_node::URGCWrapper::checkCRC ( const char *  bytes,
const uint32_t  size 
) [private]

calculate the crc of a given set of bytes.

Parameters:
bytesThe bytes array to be processed.
sizeThe size of the bytes array.
Returns:
the calculated CRC of the bytes.

Definition at line 572 of file urg_c_wrapper.cpp.

Definition at line 923 of file urg_c_wrapper.cpp.

Definition at line 716 of file urg_c_wrapper.cpp.

Definition at line 695 of file urg_c_wrapper.cpp.

Definition at line 708 of file urg_c_wrapper.cpp.

Definition at line 690 of file urg_c_wrapper.cpp.

Definition at line 700 of file urg_c_wrapper.cpp.

Definition at line 907 of file urg_c_wrapper.cpp.

Definition at line 342 of file urg_c_wrapper.cpp.

Definition at line 790 of file urg_c_wrapper.cpp.

Definition at line 785 of file urg_c_wrapper.cpp.

Definition at line 432 of file urg_c_wrapper.cpp.

Definition at line 775 of file urg_c_wrapper.cpp.

Definition at line 770 of file urg_c_wrapper.cpp.

std::string urg_node::URGCWrapper::getIPAddress ( ) const

Definition at line 740 of file urg_c_wrapper.cpp.

Definition at line 745 of file urg_c_wrapper.cpp.

ros::Duration urg_node::URGCWrapper::getNativeClockOffset ( size_t  num_measurements) [private]

Definition at line 953 of file urg_c_wrapper.cpp.

Definition at line 765 of file urg_c_wrapper.cpp.

Definition at line 780 of file urg_c_wrapper.cpp.

Definition at line 682 of file urg_c_wrapper.cpp.

Definition at line 674 of file urg_c_wrapper.cpp.

Definition at line 723 of file urg_c_wrapper.cpp.

Definition at line 805 of file urg_c_wrapper.cpp.

Definition at line 800 of file urg_c_wrapper.cpp.

Definition at line 755 of file urg_c_wrapper.cpp.

std::string urg_node::URGCWrapper::getSerialPort ( ) const

Definition at line 750 of file urg_c_wrapper.cpp.

ros::Time urg_node::URGCWrapper::getSynchronizedTime ( long  time_stamp,
long long  system_time_stamp 
) [private]

Get synchronized time stamp using hardware clock.

Parameters:
time_stampThe current hardware time stamp.
system_time_stampThe current system time stamp.
Returns:
ros::Time stamp representing synchronized time

Definition at line 1052 of file urg_c_wrapper.cpp.

Definition at line 729 of file urg_c_wrapper.cpp.

ros::Duration urg_node::URGCWrapper::getTimeStampOffset ( size_t  num_measurements) [private]

Definition at line 994 of file urg_c_wrapper.cpp.

Definition at line 795 of file urg_c_wrapper.cpp.

Definition at line 760 of file urg_c_wrapper.cpp.

bool urg_node::URGCWrapper::grabScan ( const sensor_msgs::LaserScanPtr &  msg)

Definition at line 206 of file urg_c_wrapper.cpp.

bool urg_node::URGCWrapper::grabScan ( const sensor_msgs::MultiEchoLaserScanPtr &  msg)

Definition at line 270 of file urg_c_wrapper.cpp.

void urg_node::URGCWrapper::initialize ( bool &  using_intensity,
bool &  using_multiecho,
bool  synchronize_time 
) [private]

Definition at line 97 of file urg_c_wrapper.cpp.

Definition at line 873 of file urg_c_wrapper.cpp.

Definition at line 890 of file urg_c_wrapper.cpp.

Definition at line 669 of file urg_c_wrapper.cpp.

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:
cmdThe 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 
)

Definition at line 821 of file urg_c_wrapper.cpp.

void urg_node::URGCWrapper::setFrameId ( const std::string &  frame_id)

Definition at line 810 of file urg_c_wrapper.cpp.

bool urg_node::URGCWrapper::setSkip ( int  skip)

Definition at line 868 of file urg_c_wrapper.cpp.

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)

Definition at line 815 of file urg_c_wrapper.cpp.

Definition at line 170 of file urg_c_wrapper.cpp.

Definition at line 194 of file urg_c_wrapper.cpp.


Member Data Documentation

const double urg_node::URGCWrapper::adj_alpha_ = .01 [private]

Definition at line 237 of file urg_c_wrapper.h.

Definition at line 238 of file urg_c_wrapper.h.

Definition at line 226 of file urg_c_wrapper.h.

std::vector<long> urg_node::URGCWrapper::data_ [private]

Definition at line 218 of file urg_c_wrapper.h.

Definition at line 224 of file urg_c_wrapper.h.

std::string urg_node::URGCWrapper::frame_id_ [private]

Output frame_id for each laserscan.

Definition at line 213 of file urg_c_wrapper.h.

Definition at line 234 of file urg_c_wrapper.h.

Definition at line 236 of file urg_c_wrapper.h.

std::vector<unsigned short> urg_node::URGCWrapper::intensity_ [private]

Definition at line 219 of file urg_c_wrapper.h.

std::string urg_node::URGCWrapper::ip_address_ [private]

Definition at line 240 of file urg_c_wrapper.h.

Definition at line 241 of file urg_c_wrapper.h.

Definition at line 235 of file urg_c_wrapper.h.

Definition at line 225 of file urg_c_wrapper.h.

Definition at line 223 of file urg_c_wrapper.h.

Definition at line 243 of file urg_c_wrapper.h.

std::string urg_node::URGCWrapper::serial_port_ [private]

Definition at line 242 of file urg_c_wrapper.h.

Definition at line 227 of file urg_c_wrapper.h.

Definition at line 216 of file urg_c_wrapper.h.

Definition at line 233 of file urg_c_wrapper.h.

Definition at line 229 of file urg_c_wrapper.h.

Definition at line 215 of file urg_c_wrapper.h.

Definition at line 221 of file urg_c_wrapper.h.

Definition at line 222 of file urg_c_wrapper.h.

Definition at line 230 of file urg_c_wrapper.h.


The documentation for this class was generated from the following files:


urg_node
Author(s): Chad Rockey , Mike O'Driscoll
autogenerated on Sat Jun 8 2019 19:16:00