Public Member Functions | Protected Types | Protected Attributes
Hokuyo3dNode Class Reference

List of all members.

Public Member Functions

void cbAux (const vssp::Header &Header, const vssp::AuxHeader &AuxHeader, const boost::shared_array< vssp::Aux > &auxs, const boost::chrono::microseconds &delayRead)
void cbConnect (bool success)
void cbError (const vssp::Header &Header, const std::string &message)
void cbPing (const vssp::Header &Header, const boost::chrono::microseconds &delayRead)
void cbPoint (const vssp::Header &Header, const vssp::RangeHeader &RangeHeader, const vssp::RangeIndex &RangeIndex, const boost::shared_array< uint16_t > &index, const boost::shared_array< vssp::XYZI > &points, const boost::chrono::microseconds &delayRead)
void cbSubscriber ()
 Hokuyo3dNode ()
void ping ()
bool poll ()
 ~Hokuyo3dNode ()

Protected Types

enum  PublishCycle { CYCLE_FIELD, CYCLE_FRAME, CYCLE_LINE }

Protected Attributes

sensor_msgs::PointCloud2 cloud2_
sensor_msgs::PointCloud cloud_
boost::mutex connect_mutex_
PublishCycle cycle_
vssp::VsspDriver driver_
bool enable_pc2_
bool enable_pc_
int field_
int frame_
std::string frame_id_
sensor_msgs::Imu imu_
std::string imu_frame_id_
int interlace_
std::string ip_
int line_
sensor_msgs::MagneticField mag_
std::string mag_frame_id_
ros::NodeHandle pnh_
int port_
ros::Publisher pub_imu_
ros::Publisher pub_mag_
ros::Publisher pub_pc2_
ros::Publisher pub_pc_
double range_min_
ros::Time time_ping_
ros::Time timestamp_base_

Detailed Description

Definition at line 45 of file hokuyo3d.cpp.


Member Enumeration Documentation

enum Hokuyo3dNode::PublishCycle [protected]
Enumerator:
CYCLE_FIELD 
CYCLE_FRAME 
CYCLE_LINE 

Definition at line 331 of file hokuyo3d.cpp.


Constructor & Destructor Documentation

Definition at line 203 of file hokuyo3d.cpp.

Definition at line 261 of file hokuyo3d.cpp.


Member Function Documentation

void Hokuyo3dNode::cbAux ( const vssp::Header Header,
const vssp::AuxHeader AuxHeader,
const boost::shared_array< vssp::Aux > &  auxs,
const boost::chrono::microseconds &  delayRead 
) [inline]

Definition at line 145 of file hokuyo3d.cpp.

void Hokuyo3dNode::cbConnect ( bool  success) [inline]

Definition at line 184 of file hokuyo3d.cpp.

void Hokuyo3dNode::cbError ( const vssp::Header Header,
const std::string &  message 
) [inline]

Definition at line 130 of file hokuyo3d.cpp.

void Hokuyo3dNode::cbPing ( const vssp::Header Header,
const boost::chrono::microseconds &  delayRead 
) [inline]

Definition at line 134 of file hokuyo3d.cpp.

void Hokuyo3dNode::cbPoint ( const vssp::Header Header,
const vssp::RangeHeader RangeHeader,
const vssp::RangeIndex RangeIndex,
const boost::shared_array< uint16_t > &  index,
const boost::shared_array< vssp::XYZI > &  points,
const boost::chrono::microseconds &  delayRead 
) [inline]

Definition at line 48 of file hokuyo3d.cpp.

void Hokuyo3dNode::cbSubscriber ( ) [inline]

Definition at line 269 of file hokuyo3d.cpp.

void Hokuyo3dNode::ping ( ) [inline]

Definition at line 302 of file hokuyo3d.cpp.

bool Hokuyo3dNode::poll ( ) [inline]

Definition at line 293 of file hokuyo3d.cpp.


Member Data Documentation

sensor_msgs::PointCloud2 Hokuyo3dNode::cloud2_ [protected]

Definition at line 316 of file hokuyo3d.cpp.

sensor_msgs::PointCloud Hokuyo3dNode::cloud_ [protected]

Definition at line 315 of file hokuyo3d.cpp.

boost::mutex Hokuyo3dNode::connect_mutex_ [protected]

Definition at line 322 of file hokuyo3d.cpp.

Definition at line 337 of file hokuyo3d.cpp.

Definition at line 314 of file hokuyo3d.cpp.

bool Hokuyo3dNode::enable_pc2_ [protected]

Definition at line 321 of file hokuyo3d.cpp.

bool Hokuyo3dNode::enable_pc_ [protected]

Definition at line 320 of file hokuyo3d.cpp.

int Hokuyo3dNode::field_ [protected]

Definition at line 327 of file hokuyo3d.cpp.

int Hokuyo3dNode::frame_ [protected]

Definition at line 328 of file hokuyo3d.cpp.

std::string Hokuyo3dNode::frame_id_ [protected]

Definition at line 342 of file hokuyo3d.cpp.

sensor_msgs::Imu Hokuyo3dNode::imu_ [protected]

Definition at line 317 of file hokuyo3d.cpp.

std::string Hokuyo3dNode::imu_frame_id_ [protected]

Definition at line 343 of file hokuyo3d.cpp.

int Hokuyo3dNode::interlace_ [protected]

Definition at line 340 of file hokuyo3d.cpp.

std::string Hokuyo3dNode::ip_ [protected]

Definition at line 338 of file hokuyo3d.cpp.

int Hokuyo3dNode::line_ [protected]

Definition at line 329 of file hokuyo3d.cpp.

sensor_msgs::MagneticField Hokuyo3dNode::mag_ [protected]

Definition at line 318 of file hokuyo3d.cpp.

std::string Hokuyo3dNode::mag_frame_id_ [protected]

Definition at line 344 of file hokuyo3d.cpp.

Definition at line 306 of file hokuyo3d.cpp.

int Hokuyo3dNode::port_ [protected]

Definition at line 339 of file hokuyo3d.cpp.

Definition at line 312 of file hokuyo3d.cpp.

Definition at line 313 of file hokuyo3d.cpp.

Definition at line 311 of file hokuyo3d.cpp.

Definition at line 310 of file hokuyo3d.cpp.

double Hokuyo3dNode::range_min_ [protected]

Definition at line 341 of file hokuyo3d.cpp.

Definition at line 324 of file hokuyo3d.cpp.

Definition at line 325 of file hokuyo3d.cpp.


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


hokuyo3d
Author(s): Atsushi Watanabe
autogenerated on Wed Sep 27 2017 02:52:08