#include <transform.h>
Classes | |
struct | Config |
configuration parameters More... | |
Public Member Functions | |
Transform (ros::NodeHandle node, ros::NodeHandle private_nh, std::string const &node_name=ros::this_node::getName()) | |
Constructor. More... | |
~Transform () | |
Private Member Functions | |
void | processScan (const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg) |
Callback for raw scan messages. More... | |
void | reconfigure_callback (velodyne_pointcloud::TransformNodeConfig &config, uint32_t level) |
Private Attributes | |
Config | config_ |
boost::shared_ptr< velodyne_rawdata::DataContainerBase > | container_ptr |
boost::shared_ptr< velodyne_rawdata::RawData > | data_ |
double | diag_max_freq_ |
double | diag_min_freq_ |
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > | diag_topic_ |
diagnostic_updater::Updater | diagnostics_ |
bool | first_rcfg_call |
ros::Publisher | output_ |
boost::mutex | reconfigure_mtx_ |
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_pointcloud::TransformNodeConfig > > | srv_ |
boost::shared_ptr< tf::MessageFilter< velodyne_msgs::VelodyneScan > > | tf_filter_ptr_ |
const std::string | tf_prefix_ |
boost::shared_ptr< tf::TransformListener > | tf_ptr_ |
message_filters::Subscriber< velodyne_msgs::VelodyneScan > | velodyne_scan_ |
Definition at line 61 of file transform.h.
velodyne_pointcloud::Transform::Transform | ( | ros::NodeHandle | node, |
ros::NodeHandle | private_nh, | ||
std::string const & | node_name = ros::this_node::getName() |
||
) |
Constructor.
Definition at line 29 of file transform.cc.
|
inline |
Definition at line 68 of file transform.h.
|
private |
Callback for raw scan messages.
frame_id
can succeed. Definition at line 135 of file transform.cc.
|
private |
Definition at line 94 of file transform.cc.
|
private |
Definition at line 97 of file transform.h.
|
private |
Definition at line 101 of file transform.h.
|
private |
Definition at line 80 of file transform.h.
|
private |
Definition at line 106 of file transform.h.
|
private |
Definition at line 105 of file transform.h.
|
private |
Definition at line 107 of file transform.h.
|
private |
Definition at line 104 of file transform.h.
|
private |
Definition at line 99 of file transform.h.
|
private |
Definition at line 82 of file transform.h.
|
private |
Definition at line 108 of file transform.h.
|
private |
Definition at line 76 of file transform.h.
|
private |
Definition at line 83 of file transform.h.
|
private |
Definition at line 79 of file transform.h.
|
private |
Definition at line 84 of file transform.h.
|
private |
Definition at line 81 of file transform.h.