include
velodyne_driver
driver.h
Go to the documentation of this file.
1
// Copyright (C) 2012 Austin Robot Technology, Jack O'Quin
2
// All rights reserved.
3
//
4
// Software License Agreement (BSD License 2.0)
5
//
6
// Redistribution and use in source and binary forms, with or without
7
// modification, are permitted provided that the following conditions
8
// are met:
9
//
10
// * Redistributions of source code must retain the above copyright
11
// notice, this list of conditions and the following disclaimer.
12
// * Redistributions in binary form must reproduce the above
13
// copyright notice, this list of conditions and the following
14
// disclaimer in the documentation and/or other materials provided
15
// with the distribution.
16
// * Neither the name of {copyright_holder} nor the names of its
17
// contributors may be used to endorse or promote products derived
18
// from this software without specific prior written permission.
19
//
20
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23
// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24
// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25
// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26
// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28
// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29
// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31
// POSSIBILITY OF SUCH DAMAGE.
32
33
#ifndef VELODYNE_DRIVER_DRIVER_H
34
#define VELODYNE_DRIVER_DRIVER_H
35
36
#include <string>
37
#include <
ros/ros.h
>
38
#include <
diagnostic_updater/diagnostic_updater.h
>
39
#include <
diagnostic_updater/publisher.h
>
40
#include <dynamic_reconfigure/server.h>
41
42
#include <
velodyne_driver/input.h
>
43
#include <velodyne_driver/VelodyneNodeConfig.h>
44
45
namespace
velodyne_driver
46
{
47
48
class
VelodyneDriver
49
{
50
public
:
51
VelodyneDriver
(
ros::NodeHandle
node,
52
ros::NodeHandle
private_nh,
53
std::string
const
& node_name =
ros::this_node::getName
());
54
~VelodyneDriver
() {}
55
56
bool
poll
(
void
);
57
58
private
:
59
// Callback for dynamic reconfigure
60
void
callback
(velodyne_driver::VelodyneNodeConfig &config,
61
uint32_t level);
62
// Callback for diagnostics update for lost communication with vlp
63
void
diagTimerCallback
(
const
ros::TimerEvent
&event);
64
65
// Pointer to dynamic reconfigure service srv_
66
boost::shared_ptr
<dynamic_reconfigure::Server<velodyne_driver::
67
VelodyneNodeConfig> >
srv_
;
68
69
// configuration parameters
70
struct
71
{
72
std::string
frame_id
;
// tf frame ID
73
std::string
model
;
// device model name
74
int
npackets
;
// number of packets to collect
75
double
rpm
;
// device rotation rate (RPMs)
76
int
cut_angle
;
// cutting angle in 1/100°
77
double
time_offset
;
// time in seconds added to each velodyne time stamp
78
bool
enabled
;
// polling is enabled
79
bool
timestamp_first_packet
;
80
}
81
config_
;
82
83
boost::shared_ptr<Input>
input_
;
84
ros::Publisher
output_
;
85
int
last_azimuth_
;
86
87
/* diagnostics updater */
88
ros::Timer
diag_timer_
;
89
diagnostic_updater::Updater
diagnostics_
;
90
double
diag_min_freq_
;
91
double
diag_max_freq_
;
92
boost::shared_ptr<diagnostic_updater::TopicDiagnostic>
diag_topic_
;
93
};
94
95
}
// namespace velodyne_driver
96
97
#endif // VELODYNE_DRIVER_DRIVER_H
velodyne_driver::VelodyneDriver::callback
void callback(velodyne_driver::VelodyneNodeConfig &config, uint32_t level)
Definition:
driver.cc:287
ros::Publisher
velodyne_driver::VelodyneDriver::diag_timer_
ros::Timer diag_timer_
Definition:
driver.h:88
boost::shared_ptr
velodyne_driver::VelodyneDriver::~VelodyneDriver
~VelodyneDriver()
Definition:
driver.h:54
velodyne_driver::VelodyneDriver::model
std::string model
Definition:
driver.h:73
velodyne_driver::VelodyneDriver::srv_
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_driver::VelodyneNodeConfig > > srv_
Definition:
driver.h:67
ros.h
diagnostic_updater::Updater
velodyne_driver::VelodyneDriver::output_
ros::Publisher output_
Definition:
driver.h:84
velodyne_driver::VelodyneDriver::time_offset
double time_offset
Definition:
driver.h:77
velodyne_driver::VelodyneDriver::diag_topic_
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
Definition:
driver.h:92
velodyne_driver::VelodyneDriver::cut_angle
int cut_angle
Definition:
driver.h:76
publisher.h
diagnostic_updater.h
velodyne_driver::VelodyneDriver::VelodyneDriver
VelodyneDriver(ros::NodeHandle node, ros::NodeHandle private_nh, std::string const &node_name=ros::this_node::getName())
Definition:
driver.cc:50
velodyne_driver::VelodyneDriver::diagnostics_
diagnostic_updater::Updater diagnostics_
Definition:
driver.h:89
velodyne_driver::VelodyneDriver::poll
bool poll(void)
Definition:
driver.cc:204
velodyne_driver::VelodyneDriver::rpm
double rpm
Definition:
driver.h:75
velodyne_driver::VelodyneDriver::diag_min_freq_
double diag_min_freq_
Definition:
driver.h:90
velodyne_driver::VelodyneDriver::input_
boost::shared_ptr< Input > input_
Definition:
driver.h:83
ros::TimerEvent
velodyne_driver::VelodyneDriver::enabled
bool enabled
Definition:
driver.h:78
velodyne_driver::VelodyneDriver::diagTimerCallback
void diagTimerCallback(const ros::TimerEvent &event)
Definition:
driver.cc:301
velodyne_driver::VelodyneDriver::diag_max_freq_
double diag_max_freq_
Definition:
driver.h:91
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
velodyne_driver::VelodyneDriver::frame_id
std::string frame_id
Definition:
driver.h:72
velodyne_driver::VelodyneDriver::last_azimuth_
int last_azimuth_
Definition:
driver.h:85
velodyne_driver::VelodyneDriver::npackets
int npackets
Definition:
driver.h:74
velodyne_driver
Definition:
driver.h:45
ros::Timer
input.h
velodyne_driver::VelodyneDriver::timestamp_first_packet
bool timestamp_first_packet
Definition:
driver.h:79
velodyne_driver::VelodyneDriver::config_
struct velodyne_driver::VelodyneDriver::@0 config_
ros::NodeHandle
velodyne_driver::VelodyneDriver
Definition:
driver.h:48
velodyne_driver
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Fri Aug 2 2024 08:46:21