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
ros::Duration getComputedLatency () const
std::string getDeviceID ()
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)
 URGCWrapper (const int serial_baud, const std::string &serial_port, bool &using_intensity, bool &using_multiecho)
 ~URGCWrapper ()

Private Member Functions

ros::Duration getAngularTimeOffset () const
ros::Duration getNativeClockOffset (size_t num_measurements)
ros::Duration getTimeStampOffset (size_t num_measurements)
void initialize (bool &using_intensity, bool &using_multiecho)
bool isIntensitySupported ()
bool isMultiEchoSupported ()

Private Attributes

int cluster_
std::vector< long > data_
int first_step_
std::string frame_id_
 Output frame_id for each laserscan.
std::vector< unsigned short > intensity_
std::string ip_address_
int ip_port_
int last_step_
urg_measurement_type_t measurement_type_
int serial_baud_
std::string serial_port_
int skip_
bool started_
ros::Duration system_latency_
urg_t urg_
bool use_intensity_
bool use_multiecho_
ros::Duration user_latency_

Detailed Description

Definition at line 49 of file urg_c_wrapper.h.


Constructor & Destructor Documentation

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

Definition at line 38 of file urg_c_wrapper.cpp.

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

Definition at line 61 of file urg_c_wrapper.cpp.

Definition at line 143 of file urg_c_wrapper.cpp.


Member Function Documentation

ros::Duration URGCWrapper::computeLatency ( size_t  num_measurements)

Definition at line 461 of file urg_c_wrapper.cpp.

Definition at line 292 of file urg_c_wrapper.cpp.

double URGCWrapper::getAngleMax ( ) const

Definition at line 274 of file urg_c_wrapper.cpp.

Definition at line 285 of file urg_c_wrapper.cpp.

double URGCWrapper::getAngleMin ( ) const

Definition at line 270 of file urg_c_wrapper.cpp.

Definition at line 278 of file urg_c_wrapper.cpp.

Definition at line 449 of file urg_c_wrapper.cpp.

Definition at line 353 of file urg_c_wrapper.cpp.

std::string URGCWrapper::getDeviceID ( )

Definition at line 349 of file urg_c_wrapper.cpp.

Definition at line 341 of file urg_c_wrapper.cpp.

Definition at line 337 of file urg_c_wrapper.cpp.

std::string URGCWrapper::getIPAddress ( ) const

Definition at line 313 of file urg_c_wrapper.cpp.

int URGCWrapper::getIPPort ( ) const

Definition at line 317 of file urg_c_wrapper.cpp.

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

Definition at line 488 of file urg_c_wrapper.cpp.

std::string URGCWrapper::getProductName ( )

Definition at line 333 of file urg_c_wrapper.cpp.

Definition at line 345 of file urg_c_wrapper.cpp.

double URGCWrapper::getRangeMax ( ) const

Definition at line 263 of file urg_c_wrapper.cpp.

double URGCWrapper::getRangeMin ( ) const

Definition at line 256 of file urg_c_wrapper.cpp.

double URGCWrapper::getScanPeriod ( ) const

Definition at line 298 of file urg_c_wrapper.cpp.

std::string URGCWrapper::getSensorState ( )

Definition at line 365 of file urg_c_wrapper.cpp.

Definition at line 361 of file urg_c_wrapper.cpp.

Definition at line 325 of file urg_c_wrapper.cpp.

std::string URGCWrapper::getSerialPort ( ) const

Definition at line 321 of file urg_c_wrapper.cpp.

Definition at line 303 of file urg_c_wrapper.cpp.

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

Definition at line 525 of file urg_c_wrapper.cpp.

Definition at line 357 of file urg_c_wrapper.cpp.

std::string URGCWrapper::getVendorName ( )

Definition at line 329 of file urg_c_wrapper.cpp.

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

Definition at line 148 of file urg_c_wrapper.cpp.

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

Definition at line 194 of file urg_c_wrapper.cpp.

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

Definition at line 83 of file urg_c_wrapper.cpp.

Definition at line 421 of file urg_c_wrapper.cpp.

Definition at line 435 of file urg_c_wrapper.cpp.

bool URGCWrapper::isStarted ( ) const

Definition at line 252 of file urg_c_wrapper.cpp.

bool URGCWrapper::setAngleLimitsAndCluster ( double &  angle_min,
double &  angle_max,
int  cluster 
)

Definition at line 378 of file urg_c_wrapper.cpp.

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

Definition at line 369 of file urg_c_wrapper.cpp.

bool URGCWrapper::setSkip ( int  skip)

Definition at line 417 of file urg_c_wrapper.cpp.

void URGCWrapper::setUserLatency ( const double  latency)

Definition at line 373 of file urg_c_wrapper.cpp.

Definition at line 119 of file urg_c_wrapper.cpp.

Definition at line 138 of file urg_c_wrapper.cpp.


Member Data Documentation

Definition at line 150 of file urg_c_wrapper.h.

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

Definition at line 142 of file urg_c_wrapper.h.

Definition at line 148 of file urg_c_wrapper.h.

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

Output frame_id for each laserscan.

Definition at line 137 of file urg_c_wrapper.h.

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

Definition at line 143 of file urg_c_wrapper.h.

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

Definition at line 156 of file urg_c_wrapper.h.

Definition at line 157 of file urg_c_wrapper.h.

Definition at line 149 of file urg_c_wrapper.h.

Definition at line 147 of file urg_c_wrapper.h.

Definition at line 159 of file urg_c_wrapper.h.

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

Definition at line 158 of file urg_c_wrapper.h.

Definition at line 151 of file urg_c_wrapper.h.

Definition at line 140 of file urg_c_wrapper.h.

Definition at line 153 of file urg_c_wrapper.h.

Definition at line 139 of file urg_c_wrapper.h.

Definition at line 145 of file urg_c_wrapper.h.

Definition at line 146 of file urg_c_wrapper.h.

Definition at line 154 of file urg_c_wrapper.h.


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


urg_node
Author(s): Chad Rockey
autogenerated on Fri Aug 28 2015 13:35:14