Apollo
10.0
自动驾驶开放平台
convert.h
浏览该文件的文档.
1
/******************************************************************************
2
* Copyright 2017 The Apollo Authors. All Rights Reserved.
3
*
4
* Licensed under the Apache License, Version 2.0 (the "License");
5
* you may not use this file except in compliance with the License.
6
* You may obtain a copy of the License at
7
*
8
* http://www.apache.org/licenses/LICENSE-2.0
9
*
10
* Unless required by applicable law or agreed to in writing, software
11
* distributed under the License is distributed on an "AS IS" BASIS,
12
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13
* See the License for the specific language governing permissions and
14
* limitations under the License.
15
*****************************************************************************/
16
17
#pragma once
18
19
#include <memory>
20
#include <string>
21
22
#include "modules/common_msgs/sensor_msgs/pointcloud.pb.h"
23
#include "
modules/drivers/lidar/velodyne/parser/velodyne_parser.h
"
24
#include "modules/drivers/lidar/proto/velodyne_config.pb.h"
25
#include "modules/drivers/lidar/proto/velodyne.pb.h"
26
27
namespace
apollo
{
28
namespace
drivers {
29
namespace
velodyne {
30
31
using
apollo::drivers::PointCloud
;
32
using
apollo::drivers::velodyne::VelodyneScan
;
33
34
// convert velodyne data to pointcloud and republish
35
class
Convert
{
36
public
:
37
Convert
() =
default
;
38
virtual
~Convert
() =
default
;
39
40
// init velodyne config struct from private_nh
41
// void init(ros::NodeHandle& node, ros::NodeHandle& private_nh);
42
void
init
(
const
Config
& velodyne_config);
43
44
// convert velodyne data to pointcloud and public
45
void
ConvertPacketsToPointcloud
(
const
std::shared_ptr<VelodyneScan>& scan_msg,
46
std::shared_ptr<PointCloud> point_cloud_out);
47
48
private
:
49
// RawData class for converting data to point cloud
50
std::unique_ptr<VelodyneParser> parser_;
51
52
// ros::Subscriber velodyne_scan_;
53
// ros::Publisher pointcloud_pub_;
54
55
// std::string topic_packets_;
56
std::string channel_pointcloud_;
57
59
Config
config_;
60
// queue size for ros node pub
61
// int queue_size_ = 10;
62
};
63
64
}
// namespace velodyne
65
}
// namespace drivers
66
}
// namespace apollo
apollo::drivers::velodyne::Convert
Definition
convert.h:35
apollo::drivers::velodyne::Convert::Convert
Convert()=default
apollo::drivers::velodyne::Convert::init
void init(const Config &velodyne_config)
Definition
convert.cc:26
apollo::drivers::velodyne::Convert::ConvertPacketsToPointcloud
void ConvertPacketsToPointcloud(const std::shared_ptr< VelodyneScan > &scan_msg, std::shared_ptr< PointCloud > point_cloud_out)
Callback for raw scan messages.
Definition
convert.cc:39
apollo::drivers::velodyne::Convert::~Convert
virtual ~Convert()=default
apollo
class register implement
Definition
arena_queue.h:37
apollo::drivers::PointCloud
Definition
pointcloud.proto:14
apollo::drivers::velodyne::Config
Definition
velodyne_config.proto:7
apollo::drivers::velodyne::VelodyneScan
Definition
velodyne.proto:29
velodyne_parser.h
Velodyne HDL-64E 3D LIDAR data accessors
modules
drivers
lidar
velodyne
parser
convert.h