Skip to content

Commit

Permalink
Lidar Velodyne: added pointcloud folder and util.h/cc
Browse files Browse the repository at this point in the history
  • Loading branch information
lianglia-apollo authored and ycool committed Jul 3, 2018
1 parent 74c65a1 commit b971204
Show file tree
Hide file tree
Showing 3 changed files with 118 additions and 0 deletions.
19 changes: 19 additions & 0 deletions modules/drivers/lidar_velodyne/pointcloud/lib/BUILD
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
load("//tools:cpplint.bzl", "cpplint")

package(default_visibility = ["//visibility:public"])

cc_library(
name = "util",
srcs = [
"util.cc",
],
hdrs = [
"util.h",
],
deps = [
"//modules/common",
"@ros//:ros_common",
],
)

cpplint()
34 changes: 34 additions & 0 deletions modules/drivers/lidar_velodyne/pointcloud/lib/util.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
/******************************************************************************
* Copyright 2017 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/

#include "modules/drivers/lidar_velodyne/pointcloud/lib/util.h"

namespace apollo {
namespace drivers {
namespace lidar_velodyne {

void init_sin_cos_rot_table(float* sin_rot_table, float* cos_rot_table,
uint16_t rotation, float rotation_resolution) {
for (uint16_t i = 0; i < rotation; ++i) {
float rotation = angles::from_degrees(rotation_resolution * i);
cos_rot_table[i] = cosf(rotation);
sin_rot_table[i] = sinf(rotation);
}
}

} // namespace lidar_velodyne
} // namespace drivers
} // namespace apollo
65 changes: 65 additions & 0 deletions modules/drivers/lidar_velodyne/pointcloud/lib/util.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
/******************************************************************************
* Copyright 2017 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/

#ifndef MODULES_DRIVERS_LIDAR_VELODYNE_POINTCLOUD_LIB_UTIL_H_
#define MODULES_DRIVERS_LIDAR_VELODYNE_POINTCLOUD_LIB_UTIL_H_

#include <fstream>

#include "angles/angles.h"
#include "ros/ros.h"

namespace apollo {
namespace drivers {
namespace lidar_velodyne {

template <typename T>
void dump_msg(const T& msg, const std::string& file_path) {
std::ofstream ofs(file_path.c_str(),
std::ofstream::out | std::ofstream::binary);
uint32_t serial_size = ros::serialization::serializationLength(msg);
boost::shared_array<uint8_t> obuffer(new uint8_t[serial_size]);
ros::serialization::OStream ostream(obuffer.get(), serial_size);
ros::serialization::serialize(ostream, msg);
ofs.write((char*)obuffer.get(), serial_size);
ofs.close();
}

template <class T>
void load_msg(const std::string& file_path, T* msg) {
std::ifstream ifs(file_path.c_str(),
std::ifstream::in | std::ifstream::binary);
ifs.seekg(0, std::ios::end);
std::streampos end = ifs.tellg();
ifs.seekg(0, std::ios::beg);
std::streampos begin = ifs.tellg();

uint32_t file_size = end - begin;
boost::shared_array<uint8_t> ibuffer(new uint8_t[file_size]);
ifs.read((char*)ibuffer.get(), file_size);
ros::serialization::IStream istream(ibuffer.get(), file_size);
ros::serialization::deserialize(istream, *msg);
ifs.close();
}

void init_sin_cos_rot_table(float* sin_rot_table, float* cos_rot_table,
uint16_t rotation, float rotation_resolution);

} // namespace lidar_velodyne
} // namespace drivers
} // namespace apollo

#endif // MODULES_DRIVERS_LIDAR_VELODYNE_POINTCLOUD_LIB_UTIL_H_

0 comments on commit b971204

Please sign in to comment.