|
| 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 () |
| |
Definition at line 51 of file hokuyo3d.cpp.
| Enumerator |
|---|
| CYCLE_FIELD |
|
| CYCLE_FRAME |
|
| CYCLE_LINE |
|
Definition at line 450 of file hokuyo3d.cpp.
| Hokuyo3dNode::Hokuyo3dNode |
( |
| ) |
|
|
inline |
| Hokuyo3dNode::~Hokuyo3dNode |
( |
| ) |
|
|
inline |
| void Hokuyo3dNode::cbConnect |
( |
bool |
success | ) |
|
|
inline |
| void Hokuyo3dNode::cbError |
( |
const vssp::Header & |
header, |
|
|
const std::string & |
message, |
|
|
const boost::posix_time::ptime & |
time_read |
|
) |
| |
|
inline |
| void Hokuyo3dNode::cbPing |
( |
const vssp::Header & |
header, |
|
|
const boost::posix_time::ptime & |
time_read |
|
) |
| |
|
inline |
| void Hokuyo3dNode::cbSubscriber |
( |
| ) |
|
|
inline |
| void Hokuyo3dNode::cbTimer |
( |
const boost::system::error_code & |
error | ) |
|
|
inline |
| void Hokuyo3dNode::ping |
( |
| ) |
|
|
inline |
| bool Hokuyo3dNode::poll |
( |
| ) |
|
|
inline |
| void Hokuyo3dNode::spin |
( |
| ) |
|
|
inline |
| bool Hokuyo3dNode::allow_jump_back_ |
|
protected |
| bool Hokuyo3dNode::auto_reset_ |
|
protected |
| sensor_msgs::PointCloud2 Hokuyo3dNode::cloud2_ |
|
protected |
| sensor_msgs::PointCloud Hokuyo3dNode::cloud_ |
|
protected |
| boost::mutex Hokuyo3dNode::connect_mutex_ |
|
protected |
| bool Hokuyo3dNode::enable_pc2_ |
|
protected |
| bool Hokuyo3dNode::enable_pc_ |
|
protected |
| std::string Hokuyo3dNode::frame_id_ |
|
protected |
| int Hokuyo3dNode::horizontal_interlace_ |
|
protected |
| sensor_msgs::Imu Hokuyo3dNode::imu_ |
|
protected |
| std::string Hokuyo3dNode::imu_frame_id_ |
|
protected |
| boost::asio::io_service Hokuyo3dNode::io_ |
|
protected |
| std::string Hokuyo3dNode::ip_ |
|
protected |
| sensor_msgs::MagneticField Hokuyo3dNode::mag_ |
|
protected |
| std::string Hokuyo3dNode::mag_frame_id_ |
|
protected |
| double Hokuyo3dNode::range_min_ |
|
protected |
| bool Hokuyo3dNode::set_auto_reset_ |
|
protected |
| boost::asio::deadline_timer Hokuyo3dNode::timer_ |
|
protected |
| std::deque<ros::Time> Hokuyo3dNode::timestamp_base_buffer_ |
|
protected |
| int Hokuyo3dNode::vertical_interlace_ |
|
protected |
The documentation for this class was generated from the following file: