Apollo
10.0
自动驾驶开放平台
online_calibration.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
#include <vector>
22
23
#include "modules/drivers/lidar/proto/velodyne.pb.h"
24
25
#include "
cyber/cyber.h
"
26
#include "
modules/drivers/lidar/velodyne/parser/calibration.h
"
27
28
namespace
apollo
{
29
namespace
drivers {
30
namespace
velodyne {
31
32
using
apollo::drivers::velodyne::VelodynePacket
;
33
using
apollo::drivers::velodyne::VelodyneScan
;
34
35
constexpr
double
DEGRESS_TO_RADIANS
= 3.1415926535897 / 180.0;
36
37
class
OnlineCalibration
{
38
public
:
39
OnlineCalibration
() {}
40
~OnlineCalibration
() {}
41
42
int
decode
(
const
std::shared_ptr<VelodyneScan>& scan_msgs);
43
void
dump
(
const
std::string& file_path);
44
void
get_unit_index
();
45
bool
inited
()
const
{
return
inited_; }
46
Calibration
calibration
()
const
{
return
calibration_; }
47
48
private
:
49
bool
inited_;
50
Calibration
calibration_;
51
std::vector<uint8_t> status_types_;
52
std::vector<uint8_t> status_values_;
53
// store first two "unit#" value index
54
std::vector<int> unit_indexs_;
55
};
56
57
}
// namespace velodyne
58
}
// namespace drivers
59
}
// namespace apollo
apollo::drivers::velodyne::Calibration
Calibration class storing entire configuration for the Velodyne
Definition
calibration.h:68
apollo::drivers::velodyne::OnlineCalibration
Definition
online_calibration.h:37
apollo::drivers::velodyne::OnlineCalibration::~OnlineCalibration
~OnlineCalibration()
Definition
online_calibration.h:40
apollo::drivers::velodyne::OnlineCalibration::dump
void dump(const std::string &file_path)
Definition
online_calibration.cc:140
apollo::drivers::velodyne::OnlineCalibration::decode
int decode(const std::shared_ptr< VelodyneScan > &scan_msgs)
Definition
online_calibration.cc:26
apollo::drivers::velodyne::OnlineCalibration::OnlineCalibration
OnlineCalibration()
Definition
online_calibration.h:39
apollo::drivers::velodyne::OnlineCalibration::get_unit_index
void get_unit_index()
Definition
online_calibration.cc:122
apollo::drivers::velodyne::OnlineCalibration::inited
bool inited() const
Definition
online_calibration.h:45
apollo::drivers::velodyne::OnlineCalibration::calibration
Calibration calibration() const
Definition
online_calibration.h:46
cyber.h
apollo::drivers::velodyne::DEGRESS_TO_RADIANS
constexpr double DEGRESS_TO_RADIANS
Definition
online_calibration.h:35
apollo
class register implement
Definition
arena_queue.h:37
apollo::drivers::velodyne::VelodynePacket
Definition
velodyne.proto:24
apollo::drivers::velodyne::VelodyneScan
Definition
velodyne.proto:29
calibration.h
modules
drivers
lidar
velodyne
parser
online_calibration.h