Public Member Functions | Public Attributes
myHeader Class Reference

A class to facilitate parallel use of pcl and ros header. More...

#include <header.h>

List of all members.

Public Member Functions

void fromRosHeader (std_msgs::Header rh)
 myHeader ()
 Allows same usage as ros/pcl header.
 myHeader (pcl::PCLHeader h)
 Allow implicit conversion from pcl header.
 myHeader (std_msgs::Header rh)
 Allow implicit conversion from ros header.
 myHeader (uint32_t aseq, ros::Time astamp, std::string aframe_id)
 convenience
 operator pcl::PCLHeader ()
 Allow implicit conversion to pcl header.
 operator std_msgs::Header ()
 Allow implicit conversion to ros header.
std_msgs::Header toRosHeader ()

Public Attributes

std::string frame_id
 Allows direct access as for pcl/ros header.
uint32_t seq
 Allows direct access as for pcl/ros header.
ros::Time stamp
 Allows direct access as for pcl/ros header.

Detailed Description

A class to facilitate parallel use of pcl and ros header.

Definition at line 7 of file header.h.


Constructor & Destructor Documentation

Allows same usage as ros/pcl header.

Definition at line 4 of file header.cpp.

myHeader::myHeader ( pcl::PCLHeader  h)

Allow implicit conversion from pcl header.

Definition at line 9 of file header.cpp.

Allow implicit conversion from ros header.

Definition at line 14 of file header.cpp.

myHeader::myHeader ( uint32_t  aseq,
ros::Time  astamp,
std::string  aframe_id 
)

convenience

Definition at line 18 of file header.cpp.


Member Function Documentation

Definition at line 35 of file header.cpp.

myHeader::operator pcl::PCLHeader ( )

Allow implicit conversion to pcl header.

Definition at line 42 of file header.cpp.

myHeader::operator std_msgs::Header ( )

Allow implicit conversion to ros header.

Definition at line 46 of file header.cpp.

Definition at line 25 of file header.cpp.


Member Data Documentation

std::string myHeader::frame_id

Allows direct access as for pcl/ros header.

Definition at line 22 of file header.h.

uint32_t myHeader::seq

Allows direct access as for pcl/ros header.

Definition at line 20 of file header.h.

Allows direct access as for pcl/ros header.

Definition at line 21 of file header.h.


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


rgbdslam_v2
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Thu Jun 6 2019 21:49:45