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 &aux_header, const boost::shared_array< vssp::Aux > &auxs, const boost::posix_time::ptime &time_read)
void cbConnect (bool success)
void cbError (const vssp::Header &header, const std::string &message, const boost::posix_time::ptime &time_read)
void cbPing (const vssp::Header &header, const boost::posix_time::ptime &time_read)
void cbPoint (const vssp::Header &header, const vssp::RangeHeader &range_header, const vssp::RangeIndex &range_index, const boost::shared_array< uint16_t > &index, const boost::shared_array< vssp::XYZI > &points, const boost::posix_time::ptime &time_read)
void cbSubscriber ()
void cbTimer (const boost::system::error_code &error)
 Hokuyo3dNode ()
void ping ()
bool poll ()
void spin ()
 ~Hokuyo3dNode ()

Protected Types

enum  PublishCycle { CYCLE_FIELD, CYCLE_FRAME, CYCLE_LINE }

Protected Attributes

bool allow_jump_back_
bool auto_reset_
sensor_msgs::PointCloud2 cloud2_
sensor_msgs::PointCloud cloud_
ros::Time cloud_stamp_last_
boost::mutex connect_mutex_
PublishCycle cycle_
vssp::VsspDriver driver_
bool enable_pc2_
bool enable_pc_
int field_
int frame_
std::string frame_id_
int horizontal_interlace_
sensor_msgs::Imu imu_
std::string imu_frame_id_
ros::Time imu_stamp_last_
boost::asio::io_service io_
std::string ip_
int line_
sensor_msgs::MagneticField mag_
std::string mag_frame_id_
ros::Time mag_stamp_last_
ros::NodeHandle pnh_
int port_
ros::Publisher pub_imu_
ros::Publisher pub_mag_
ros::Publisher pub_pc2_
ros::Publisher pub_pc_
double range_min_
bool set_auto_reset_
ros::Time time_ping_
boost::asio::deadline_timer timer_
ros::Time timestamp_base_
std::deque< ros::Timetimestamp_base_buffer_
int vertical_interlace_

Detailed Description

Definition at line 51 of file hokuyo3d.cpp.


Member Enumeration Documentation

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

Definition at line 450 of file hokuyo3d.cpp.


Constructor & Destructor Documentation

Definition at line 266 of file hokuyo3d.cpp.

Definition at line 342 of file hokuyo3d.cpp.


Member Function Documentation

void Hokuyo3dNode::cbAux ( const vssp::Header header,
const vssp::AuxHeader aux_header,
const boost::shared_array< vssp::Aux > &  auxs,
const boost::posix_time::ptime &  time_read 
) [inline]

Definition at line 186 of file hokuyo3d.cpp.

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

Definition at line 244 of file hokuyo3d.cpp.

void Hokuyo3dNode::cbError ( const vssp::Header header,
const std::string &  message,
const boost::posix_time::ptime &  time_read 
) [inline]

Definition at line 156 of file hokuyo3d.cpp.

void Hokuyo3dNode::cbPing ( const vssp::Header header,
const boost::posix_time::ptime &  time_read 
) [inline]

Definition at line 163 of file hokuyo3d.cpp.

void Hokuyo3dNode::cbPoint ( const vssp::Header header,
const vssp::RangeHeader range_header,
const vssp::RangeIndex range_index,
const boost::shared_array< uint16_t > &  index,
const boost::shared_array< vssp::XYZI > &  points,
const boost::posix_time::ptime &  time_read 
) [inline]

Definition at line 54 of file hokuyo3d.cpp.

void Hokuyo3dNode::cbSubscriber ( ) [inline]

Definition at line 350 of file hokuyo3d.cpp.

void Hokuyo3dNode::cbTimer ( const boost::system::error_code &  error) [inline]

Definition at line 383 of file hokuyo3d.cpp.

void Hokuyo3dNode::ping ( ) [inline]

Definition at line 413 of file hokuyo3d.cpp.

bool Hokuyo3dNode::poll ( ) [inline]

Definition at line 374 of file hokuyo3d.cpp.

void Hokuyo3dNode::spin ( ) [inline]

Definition at line 400 of file hokuyo3d.cpp.


Member Data Documentation

Definition at line 433 of file hokuyo3d.cpp.

bool Hokuyo3dNode::auto_reset_ [protected]

Definition at line 465 of file hokuyo3d.cpp.

sensor_msgs::PointCloud2 Hokuyo3dNode::cloud2_ [protected]

Definition at line 427 of file hokuyo3d.cpp.

sensor_msgs::PointCloud Hokuyo3dNode::cloud_ [protected]

Definition at line 426 of file hokuyo3d.cpp.

Definition at line 441 of file hokuyo3d.cpp.

boost::mutex Hokuyo3dNode::connect_mutex_ [protected]

Definition at line 434 of file hokuyo3d.cpp.

Definition at line 456 of file hokuyo3d.cpp.

Definition at line 425 of file hokuyo3d.cpp.

bool Hokuyo3dNode::enable_pc2_ [protected]

Definition at line 432 of file hokuyo3d.cpp.

bool Hokuyo3dNode::enable_pc_ [protected]

Definition at line 431 of file hokuyo3d.cpp.

int Hokuyo3dNode::field_ [protected]

Definition at line 446 of file hokuyo3d.cpp.

int Hokuyo3dNode::frame_ [protected]

Definition at line 447 of file hokuyo3d.cpp.

std::string Hokuyo3dNode::frame_id_ [protected]

Definition at line 462 of file hokuyo3d.cpp.

Definition at line 459 of file hokuyo3d.cpp.

sensor_msgs::Imu Hokuyo3dNode::imu_ [protected]

Definition at line 428 of file hokuyo3d.cpp.

std::string Hokuyo3dNode::imu_frame_id_ [protected]

Definition at line 463 of file hokuyo3d.cpp.

Definition at line 439 of file hokuyo3d.cpp.

boost::asio::io_service Hokuyo3dNode::io_ [protected]

Definition at line 443 of file hokuyo3d.cpp.

std::string Hokuyo3dNode::ip_ [protected]

Definition at line 457 of file hokuyo3d.cpp.

int Hokuyo3dNode::line_ [protected]

Definition at line 448 of file hokuyo3d.cpp.

sensor_msgs::MagneticField Hokuyo3dNode::mag_ [protected]

Definition at line 429 of file hokuyo3d.cpp.

std::string Hokuyo3dNode::mag_frame_id_ [protected]

Definition at line 464 of file hokuyo3d.cpp.

Definition at line 440 of file hokuyo3d.cpp.

Definition at line 420 of file hokuyo3d.cpp.

int Hokuyo3dNode::port_ [protected]

Definition at line 458 of file hokuyo3d.cpp.

Definition at line 423 of file hokuyo3d.cpp.

Definition at line 424 of file hokuyo3d.cpp.

Definition at line 422 of file hokuyo3d.cpp.

Definition at line 421 of file hokuyo3d.cpp.

double Hokuyo3dNode::range_min_ [protected]

Definition at line 461 of file hokuyo3d.cpp.

Definition at line 466 of file hokuyo3d.cpp.

Definition at line 436 of file hokuyo3d.cpp.

boost::asio::deadline_timer Hokuyo3dNode::timer_ [protected]

Definition at line 444 of file hokuyo3d.cpp.

Definition at line 437 of file hokuyo3d.cpp.

Definition at line 438 of file hokuyo3d.cpp.

Definition at line 460 of file hokuyo3d.cpp.


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


hokuyo3d
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 6 2019 20:08:29