Main Page
Namespaces
Classes
Files
File List
File Members
src
driver
driver.h
Go to the documentation of this file.
1
/* -*- mode: C++ -*- */
2
/*
3
* License: Modified BSD Software License Agreement
4
*
5
* $Id$
6
*/
7
13
#ifndef _O3M151_DRIVER_H_
14
#define _O3M151_DRIVER_H_ 1
15
16
#include <string>
17
#include <
ros/ros.h
>
18
#include <
pcl_ros/point_cloud.h
>
19
#include <
diagnostic_updater/diagnostic_updater.h
>
20
#include <
diagnostic_updater/publisher.h
>
21
#include <pcl/visualization/cloud_viewer.h>
22
23
#include <
o3m151_driver/input.h
>
24
25
namespace
o3m151_driver
26
{
27
28
class
O3M151Driver
29
{
30
public
:
31
32
O3M151Driver
(
ros::NodeHandle
node,
33
ros::NodeHandle
private_nh);
34
~O3M151Driver
() {}
35
36
bool
poll
(
void
);
37
38
private
:
39
40
// configuration parameters
41
std::string
frame_id_
;
42
43
boost::shared_ptr<Input>
input_
;
44
ros::Publisher
output_
;
45
47
diagnostic_updater::Updater
diagnostics_
;
48
double
diag_min_freq_
;
49
double
diag_max_freq_
;
50
boost::shared_ptr<diagnostic_updater::TopicDiagnostic>
diag_topic_
;
51
boost::shared_ptr<pcl::visualization::PCLVisualizer>
viewer_
;
52
};
53
54
}
// namespace o3m151_driver
55
56
#endif // _O3M151_DRIVER_H_
o3m151_driver::O3M151Driver::diag_max_freq_
double diag_max_freq_
Definition:
driver.h:49
o3m151_driver::O3M151Driver::diag_topic_
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
Definition:
driver.h:50
o3m151_driver::O3M151Driver::O3M151Driver
O3M151Driver(ros::NodeHandle node, ros::NodeHandle private_nh)
Definition:
driver.cc:24
ros::NodeHandle
input.h
o3m151_driver::O3M151Driver
Definition:
driver.h:28
o3m151_driver::O3M151Driver::frame_id_
std::string frame_id_
tf frame ID
Definition:
driver.h:41
o3m151_driver::O3M151Driver::viewer_
boost::shared_ptr< pcl::visualization::PCLVisualizer > viewer_
Definition:
driver.h:51
o3m151_driver
Definition:
input.h:38
diagnostic_updater.h
boost::shared_ptr
diagnostic_updater::Updater
o3m151_driver::O3M151Driver::input_
boost::shared_ptr< Input > input_
Definition:
driver.h:43
o3m151_driver::O3M151Driver::~O3M151Driver
~O3M151Driver()
Definition:
driver.h:34
o3m151_driver::O3M151Driver::output_
ros::Publisher output_
Definition:
driver.h:44
point_cloud.h
ros.h
o3m151_driver::O3M151Driver::diag_min_freq_
double diag_min_freq_
Definition:
driver.h:48
o3m151_driver::O3M151Driver::poll
bool poll(void)
Definition:
driver.cc:66
o3m151_driver::O3M151Driver::diagnostics_
diagnostic_updater::Updater diagnostics_
Definition:
driver.h:47
publisher.h
ros::Publisher
o3m151_driver
Author(s): Vincent Rousseau
autogenerated on Mon Jun 10 2019 14:07:55