Skip to content

Commit b971204

Browse files
lianglia-apolloycool
authored andcommitted
Lidar Velodyne: added pointcloud folder and util.h/cc
1 parent 74c65a1 commit b971204

File tree

3 files changed

+118
-0
lines changed

3 files changed

+118
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
load("//tools:cpplint.bzl", "cpplint")
2+
3+
package(default_visibility = ["//visibility:public"])
4+
5+
cc_library(
6+
name = "util",
7+
srcs = [
8+
"util.cc",
9+
],
10+
hdrs = [
11+
"util.h",
12+
],
13+
deps = [
14+
"//modules/common",
15+
"@ros//:ros_common",
16+
],
17+
)
18+
19+
cpplint()
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
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+
#include "modules/drivers/lidar_velodyne/pointcloud/lib/util.h"
18+
19+
namespace apollo {
20+
namespace drivers {
21+
namespace lidar_velodyne {
22+
23+
void init_sin_cos_rot_table(float* sin_rot_table, float* cos_rot_table,
24+
uint16_t rotation, float rotation_resolution) {
25+
for (uint16_t i = 0; i < rotation; ++i) {
26+
float rotation = angles::from_degrees(rotation_resolution * i);
27+
cos_rot_table[i] = cosf(rotation);
28+
sin_rot_table[i] = sinf(rotation);
29+
}
30+
}
31+
32+
} // namespace lidar_velodyne
33+
} // namespace drivers
34+
} // namespace apollo
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
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+
#ifndef MODULES_DRIVERS_LIDAR_VELODYNE_POINTCLOUD_LIB_UTIL_H_
18+
#define MODULES_DRIVERS_LIDAR_VELODYNE_POINTCLOUD_LIB_UTIL_H_
19+
20+
#include <fstream>
21+
22+
#include "angles/angles.h"
23+
#include "ros/ros.h"
24+
25+
namespace apollo {
26+
namespace drivers {
27+
namespace lidar_velodyne {
28+
29+
template <typename T>
30+
void dump_msg(const T& msg, const std::string& file_path) {
31+
std::ofstream ofs(file_path.c_str(),
32+
std::ofstream::out | std::ofstream::binary);
33+
uint32_t serial_size = ros::serialization::serializationLength(msg);
34+
boost::shared_array<uint8_t> obuffer(new uint8_t[serial_size]);
35+
ros::serialization::OStream ostream(obuffer.get(), serial_size);
36+
ros::serialization::serialize(ostream, msg);
37+
ofs.write((char*)obuffer.get(), serial_size);
38+
ofs.close();
39+
}
40+
41+
template <class T>
42+
void load_msg(const std::string& file_path, T* msg) {
43+
std::ifstream ifs(file_path.c_str(),
44+
std::ifstream::in | std::ifstream::binary);
45+
ifs.seekg(0, std::ios::end);
46+
std::streampos end = ifs.tellg();
47+
ifs.seekg(0, std::ios::beg);
48+
std::streampos begin = ifs.tellg();
49+
50+
uint32_t file_size = end - begin;
51+
boost::shared_array<uint8_t> ibuffer(new uint8_t[file_size]);
52+
ifs.read((char*)ibuffer.get(), file_size);
53+
ros::serialization::IStream istream(ibuffer.get(), file_size);
54+
ros::serialization::deserialize(istream, *msg);
55+
ifs.close();
56+
}
57+
58+
void init_sin_cos_rot_table(float* sin_rot_table, float* cos_rot_table,
59+
uint16_t rotation, float rotation_resolution);
60+
61+
} // namespace lidar_velodyne
62+
} // namespace drivers
63+
} // namespace apollo
64+
65+
#endif // MODULES_DRIVERS_LIDAR_VELODYNE_POINTCLOUD_LIB_UTIL_H_

0 commit comments

Comments
 (0)