Skip to content

Commit

Permalink
Merge pull request #3 from lnexenl/master
Browse files Browse the repository at this point in the history
Make MINS working with pcl 1.12 and Eigen 3.4 
Note: No notable performance change.
  • Loading branch information
WoosikLee2510 authored Oct 11, 2023
2 parents 9642045 + 51243a5 commit 4e09a0f
Show file tree
Hide file tree
Showing 267 changed files with 2,647 additions and 383,001 deletions.
27 changes: 27 additions & 0 deletions .github/workflows/docker-image.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
name: Docker Image CI

on:
push:
branches: [ "master" ]
pull_request:
branches: [ "master" ]

jobs:

build-melodic:

runs-on: ubuntu-latest

steps:
- uses: actions/checkout@v3
- name: Build the Docker image
run: docker build . --file Dockerfile_melodic_18_04 --tag mins:melodic

build-noetic:

runs-on: ubuntu-latest

steps:
- uses: actions/checkout@v3
- name: Build the Docker image
run: docker build . --file Dockerfile_noetic_20_04 --tag mins:noetic
7 changes: 7 additions & 0 deletions Dockerfile_melodic_18_04
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
FROM ros:melodic-perception-bionic
COPY . /catkin_ws/src/MINS
RUN apt update && apt install python3-catkin-tools -y
RUN /bin/bash -c "chmod +x /opt/ros/melodic/setup.sh && source /opt/ros/melodic/setup.sh && catkin build --workspace /catkin_ws"

WORKDIR /catkin_ws
ENTRYPOINT ["/bin/bash"]
7 changes: 7 additions & 0 deletions Dockerfile_noetic_20_04
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
FROM ros:noetic-perception-focal
COPY . /catkin_ws/src/MINS
RUN apt update && apt install python3-catkin-tools -y
RUN /bin/bash -c "chmod +x /opt/ros/noetic/setup.sh && source /opt/ros/noetic/setup.sh && catkin build --workspace /catkin_ws"

WORKDIR /catkin_ws
ENTRYPOINT ["/bin/bash"]
10 changes: 5 additions & 5 deletions mins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,13 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3 -fsee -fomit-frame-pointer -fno-sign
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g3 -Wall -Wuninitialized -Wmaybe-uninitialized -fno-omit-frame-pointer")

# Find ROS build system
find_package(catkin REQUIRED COMPONENTS roscpp rosbag tf std_msgs geometry_msgs sensor_msgs nav_msgs image_geometry visualization_msgs image_transport cv_bridge ov_core pcl_ros libpointmatcher)
find_package(catkin REQUIRED COMPONENTS roscpp rosbag tf std_msgs geometry_msgs sensor_msgs nav_msgs image_geometry visualization_msgs image_transport cv_bridge ov_core pcl_ros)

add_definitions(-DROS_AVAILABLE=1)

# Add catkin packages
catkin_package(
CATKIN_DEPENDS roscpp rosbag tf std_msgs geometry_msgs sensor_msgs nav_msgs image_geometry visualization_msgs image_transport cv_bridge ov_core pcl_ros libpointmatcher
CATKIN_DEPENDS roscpp rosbag tf std_msgs geometry_msgs sensor_msgs nav_msgs image_geometry visualization_msgs image_transport cv_bridge ov_core pcl_ros
INCLUDE_DIRS src/
LIBRARIES mins_lib
)
Expand Down Expand Up @@ -127,23 +127,23 @@ install(DIRECTORY src/
##################################################

add_executable(simulation src/run_simulation.cpp)
target_link_libraries(simulation mins_lib ${thirdparty_libraries})
target_link_libraries(simulation mins_lib)
install(TARGETS simulation
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

add_executable(bag src/run_bag.cpp)
target_link_libraries(bag mins_lib ${thirdparty_libraries})
target_link_libraries(bag mins_lib)
install(TARGETS bag
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

add_executable(subscribe src/run_subscribe.cpp)
target_link_libraries(subscribe mins_lib ${thirdparty_libraries})
target_link_libraries(subscribe mins_lib)
install(TARGETS subscribe
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
Expand Down
4 changes: 2 additions & 2 deletions mins/src/core/ROSHelper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,8 +116,8 @@ ov_core::ImuData ROSHelper::Imu2Data(const Imu::ConstPtr &msg) {
return message;
}

boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> ROSHelper::rosPC2pclPC(const sensor_msgs::PointCloud2ConstPtr &msg, int id) {
boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> pcl_pc2(new pcl::PointCloud<pcl::PointXYZ>);
std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> ROSHelper::rosPC2pclPC(const sensor_msgs::PointCloud2ConstPtr &msg, int id) {
std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> pcl_pc2(new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg(*msg, *pcl_pc2);
pcl_pc2->header.frame_id = to_string(id); // overwrite the id match with system number
pcl_pc2->header.stamp = msg->header.stamp.toSec() * 1000; // deliver this in msec
Expand Down
2 changes: 1 addition & 1 deletion mins/src/core/ROSHelper.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ class ROSHelper {

static GPSData PoseStamped2Data(const geometry_msgs::PoseStampedPtr &msg, int id, double noise);

static boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> rosPC2pclPC(const sensor_msgs::PointCloud2ConstPtr &msg, int id);
static std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> rosPC2pclPC(const sensor_msgs::PointCloud2ConstPtr &msg, int id);

static GPSData NavSatFix2Data(const sensor_msgs::NavSatFixPtr &msg, int id);

Expand Down
8 changes: 5 additions & 3 deletions mins/src/core/ROSPublisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -419,7 +419,7 @@ void ROSPublisher::publish_vicon(ViconData data) {
seq_vicon[data.id]++;
}

void ROSPublisher::publish_lidar_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr lidar) {
void ROSPublisher::publish_lidar_cloud(std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar) {
sensor_msgs::PointCloud2 output;
pcl::toROSMsg(*lidar, output);
output.header.frame_id = "lidar" + lidar->header.frame_id;
Expand Down Expand Up @@ -465,13 +465,15 @@ void ROSPublisher::publish_lidar_map() {

// Publish pointcloud in the global frame
// This is slower because it requires pointcloud transform
pcl::PointCloud<pcl::PointXYZI>::Ptr map_inL(new pcl::PointCloud<pcl::PointXYZI>);
POINTCLOUD_XYZI_PTR map_inL(new pcl::PointCloud<pcl::PointXYZI>);
ikd->tree->flatten(ikd->tree->Root_Node, map_inL->points, NOT_RECORD);
pair<Matrix3d, Vector3d> pose_LinG = sys->up_ldr->get_pose_LinG(ikd->id, ikd->time);
Matrix4d tr = Matrix4d::Identity();
tr.block(0, 0, 3, 3) = pose_LinG.first.transpose();
tr.block(0, 3, 3, 1) = pose_LinG.second;
pcl::PointCloud<pcl::PointXYZI>::Ptr map_inG(new pcl::PointCloud<pcl::PointXYZI>);
POINTCLOUD_XYZI_PTR map_inG(new pcl::PointCloud<pcl::PointXYZI>);
map_inL->height = map_inL->points.size();
map_inL->width = 1;
pcl::transformPointCloud(*map_inL, *map_inG, tr);
sensor_msgs::PointCloud2 map_pointcloud;
pcl::toROSMsg(*map_inG, map_pointcloud);
Expand Down
2 changes: 1 addition & 1 deletion mins/src/core/ROSPublisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ class ROSPublisher {
void publish_cam_images(int cam_id);

/// Publish lidar point cloud
void publish_lidar_cloud(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar);
void publish_lidar_cloud(std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar);

private:
/// Publish the current state
Expand Down
2 changes: 1 addition & 1 deletion mins/src/core/ROSSubscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,7 @@ void ROSSubscriber::callback_gnss(const NavSatFixConstPtr &msg, int gps_id) {

void ROSSubscriber::callback_lidar(const PointCloud2ConstPtr &msg, int lidar_id) {
// convert into correct format & send it to our system
boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> data = ROSHelper::rosPC2pclPC(msg, lidar_id);
std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> data = ROSHelper::rosPC2pclPC(msg, lidar_id);
sys->feed_measurement_lidar(data);
pub->publish_lidar_cloud(data);
}
2 changes: 1 addition & 1 deletion mins/src/core/SystemManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,7 @@ void SystemManager::feed_measurement_wheel(const WheelData &wheel) {
state->initialized ? tc_sensors->dong("WHL") : void();
}

void SystemManager::feed_measurement_lidar(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar) {
void SystemManager::feed_measurement_lidar(std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar) {
if (!state->op->lidar->enabled)
return;
state->initialized ? tc_sensors->ding("LDR") : void();
Expand Down
2 changes: 1 addition & 1 deletion mins/src/core/SystemManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ class SystemManager {
void feed_measurement_wheel(const WheelData &wheel);

/// LiDAR measurement feeder
void feed_measurement_lidar(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar);
void feed_measurement_lidar(std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar);
/**
* @brief After the run has ended, print results
*/
Expand Down
2 changes: 1 addition & 1 deletion mins/src/init/Initializer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -321,7 +321,7 @@ void Initializer::init_lidar_sim() {
}

// Get the lidar point cloud
boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar(new pcl::PointCloud<pcl::PointXYZ>);
std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar(new pcl::PointCloud<pcl::PointXYZ>);
bool success = sim->get_lidar_pointcloud(lidar, sim->timestamp - op->dt.at(i), i, op);
assert(success);

Expand Down
1 change: 1 addition & 0 deletions mins/src/options/OptionsIMU.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#define MINS_OPTIONSIMU_H

#include <memory>
#include <string>

namespace ov_core {
class YamlParser;
Expand Down
1 change: 1 addition & 0 deletions mins/src/options/OptionsInit.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#define MINS_OPTIONSINIT_H

#include <memory>
#include <string>
namespace ov_core {
class YamlParser;
}
Expand Down
1 change: 1 addition & 0 deletions mins/src/options/OptionsSystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#define MINS_OPTIONSSYSTEM_H

#include <memory>
#include <string>
namespace ov_core {
class YamlParser;
}
Expand Down
8 changes: 1 addition & 7 deletions mins/src/run_bag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ int main(int argc, char **argv) {
if (op->est->lidar->enabled) {
for (int lidar_id = 0; lidar_id < op->est->lidar->max_n; lidar_id++) {
if (msgs.at(i).getTopic() == op->est->lidar->topic.at(lidar_id)) {
pcl::PointCloud<pcl::PointXYZ>::Ptr data = ROSHelper::rosPC2pclPC(msgs.at(i).instantiate<sensor_msgs::PointCloud2>(), lidar_id);
std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> data = ROSHelper::rosPC2pclPC(msgs.at(i).instantiate<sensor_msgs::PointCloud2>(), lidar_id);
PRINT1("[BAG] LDR measurement: %.3f|%d|%d\n", (double)data->header.stamp / 1000, lidar_id, data->points.size());
sys->feed_measurement_lidar(data);
pub->publish_lidar_cloud(data);
Expand Down Expand Up @@ -198,12 +198,6 @@ int main(int argc, char **argv) {
op->sys->save_timing ? save->save_timing_to_file(sys->tc_sensors->get_total_sum()) : void();
save->check_files();

// Call destructor for a cleaner termination
sys->~SystemManager();
pub->~ROSPublisher();
sim_viz->~SimVisualizer();
op->~Options();
save->~State_Logger();
ros::shutdown();

// Done!
Expand Down
9 changes: 1 addition & 8 deletions mins/src/run_simulation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ int main(int argc, char **argv) {
}

// LIDAR: get the next simulated lidar range measurements
pcl::PointCloud<pcl::PointXYZ>::Ptr lidar(new pcl::PointCloud<pcl::PointXYZ>);
std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar(new pcl::PointCloud<pcl::PointXYZ>);
if (sim->get_next_lidar(lidar)) {
sys->feed_measurement_lidar(lidar);
pub->publish_lidar_cloud(lidar);
Expand All @@ -129,13 +129,6 @@ int main(int argc, char **argv) {
op->sys->save_timing ? save->save_timing_to_file(sys->tc_sensors->get_total_sum()) : void();
save->check_files();

// Call destructor for a cleaner termination
sys->~SystemManager();
sim->~Simulator();
pub->~ROSPublisher();
sim_viz->~SimVisualizer();
op->~Options();
save->~State_Logger();
ros::shutdown();
return EXIT_SUCCESS;
}
Expand Down
5 changes: 0 additions & 5 deletions mins/src/run_subscribe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,11 +80,6 @@ int main(int argc, char **argv) {
op->sys->save_timing ? save->save_timing_to_file(sys->tc_sensors->get_total_sum()) : void();
save->check_files();

// Call destructor for a cleaner termination
sys->~SystemManager();
pub->~ROSPublisher();
op->~Options();
save->~State_Logger();
ros::shutdown();

// Done!
Expand Down
4 changes: 2 additions & 2 deletions mins/src/sim/Simulator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -718,7 +718,7 @@ bool Simulator::get_next_wheel(WheelData &wheel) {
return true;
}

bool Simulator::get_next_lidar(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar) {
bool Simulator::get_next_lidar(std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar) {

// check turn
string sensor_type;
Expand All @@ -739,7 +739,7 @@ bool Simulator::get_next_lidar(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>>
return true;
}

bool Simulator::get_lidar_pointcloud(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar, double time, int id, std::shared_ptr<OptionsLidar> lidar_op) {
bool Simulator::get_lidar_pointcloud(std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar, double time, int id, std::shared_ptr<OptionsLidar> lidar_op) {
// Lidar id and timestamp
lidar->header.frame_id = to_string(id);
lidar->header.stamp = (unsigned long)((time - lidar_op->dt.at(id)) * 1000); // Delivered in micro second
Expand Down
4 changes: 2 additions & 2 deletions mins/src/sim/Simulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ class Simulator {
* @param lidar mins::LidarData
* @return True if we have a measurement
*/
bool get_next_lidar(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar);
bool get_next_lidar(std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar);

/// boolean for transforming groundtruth after GPS initialization
bool trans_gt_to_ENU = false;
Expand Down Expand Up @@ -186,7 +186,7 @@ class Simulator {
bool load_plane_data(std::string path_planes);

/// Generate LiDAR pointcloud
bool get_lidar_pointcloud(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar, double time, int id, std::shared_ptr<OptionsLidar> lidar_op);
bool get_lidar_pointcloud(std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar, double time, int id, std::shared_ptr<OptionsLidar> lidar_op);

/**
* @brief Will generate points in the fov of the specified camera
Expand Down
8 changes: 4 additions & 4 deletions mins/src/update/lidar/LidarHelper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,14 +89,14 @@ bool LidarHelper::remove_motion_blur(shared_ptr<State> state, shared_ptr<LiDARDa
void LidarHelper::downsample(shared_ptr<LiDARData> lidar, double downsample_size) {
pcl::VoxelGrid<pcl::PointXYZI> downSizeFilter;
downSizeFilter.setLeafSize((float)downsample_size, (float)downsample_size, (float)downsample_size);
downSizeFilter.setInputCloud(lidar->pointcloud);
downSizeFilter.setInputCloud((*lidar->pointcloud).makeShared());
downSizeFilter.filter(*lidar->pointcloud);
}

void LidarHelper::downsample(POINTCLOUD_XYZI_PTR lidar, double downsample_size) {
pcl::VoxelGrid<pcl::PointXYZI> downSizeFilter;
downSizeFilter.setLeafSize((float)downsample_size, (float)downsample_size, (float)downsample_size);
downSizeFilter.setInputCloud(lidar);
downSizeFilter.setInputCloud((*lidar).makeShared());
downSizeFilter.filter(*lidar);
}

Expand Down Expand Up @@ -154,7 +154,7 @@ bool LidarHelper::transform_to_map(shared_ptr<State> state, shared_ptr<LiDARData
// Run ICP if we use it to register the map
//===================================================================
if (state->op->lidar->map_use_icp) {
POINTCLOUD_XYZI_PTR map_pointcloud = boost::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
POINTCLOUD_XYZI_PTR map_pointcloud = std::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
ikd->tree->flatten(ikd->tree->Root_Node, map_pointcloud->points, NOT_RECORD);
POINTCLOUD_XYZI_PTR new_pointcloud = lidar->pointcloud;

Expand Down Expand Up @@ -209,7 +209,7 @@ void LidarHelper::register_scan(shared_ptr<State> state, shared_ptr<LiDARData> l
void LidarHelper::propagate_map_to_newest_clone(shared_ptr<State> state, shared_ptr<iKDDATA> ikd, shared_ptr<OptionsLidar> op, double FT) {

// Load map info
POINTCLOUD_XYZI_PTR map_points = boost::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
POINTCLOUD_XYZI_PTR map_points = std::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
ikd->tree->flatten(ikd->tree->Root_Node, map_points->points, NOT_RECORD);
op->map_do_downsample ? downsample(map_points, state->op->lidar->map_downsample_size) : void();

Expand Down
2 changes: 1 addition & 1 deletion mins/src/update/lidar/LidarHelper.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class PointXYZ;
class PointXYZI;
template <class pointT> class PointCloud;
} // namespace pcl
typedef boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI>> POINTCLOUD_XYZI_PTR;
typedef std::shared_ptr<pcl::PointCloud<pcl::PointXYZI>> POINTCLOUD_XYZI_PTR;
template <class pointT> class KD_TREE;
namespace mins {
class State;
Expand Down
14 changes: 7 additions & 7 deletions mins/src/update/lidar/LidarTypes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,14 +23,14 @@
#include "pcl/point_cloud.h"

using namespace mins;
LiDARData::LiDARData(double time, double ref_time, int id, boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> pointcloud, double max_range, double min_range) : time(time), id(id) {
LiDARData::LiDARData(double time, double ref_time, int id, std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> pointcloud, double max_range, double min_range) : time(time), id(id) {
// copy over the point cloud
// copy measurement time of the point so that it can be filtered with time.
// Note: we only store relative time to "reference time" because intensity (float) has only 4 bytes
// Note: this "reference time" should be the same for all other pointclouds.
this->pointcloud = boost::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
this->pointcloud_original = boost::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
this->pointcloud_in_map = boost::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
this->pointcloud = std::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
this->pointcloud_original = std::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
this->pointcloud_in_map = std::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
this->pointcloud->points.reserve(pointcloud->points.size());
this->pointcloud_original->points.reserve(pointcloud->points.size());
for (int i = 0; i < (int)pointcloud->size(); i++) {
Expand Down Expand Up @@ -58,9 +58,9 @@ LiDARData::LiDARData(double time, double ref_time, int id, boost::shared_ptr<pcl
LiDARData::LiDARData() {
time = -1;
id = -1;
pointcloud = boost::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
pointcloud_original = boost::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
pointcloud_in_map = boost::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
pointcloud = std::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
pointcloud_original = std::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
pointcloud_in_map = std::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
}

Eigen::Vector3d LiDARData::p(int p_id) {
Expand Down
4 changes: 2 additions & 2 deletions mins/src/update/lidar/LidarTypes.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,12 +30,12 @@ class PointXYZ;
class PointXYZI;
template <class pointT> class PointCloud;
} // namespace pcl
typedef boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI>> POINTCLOUD_XYZI_PTR;
typedef std::shared_ptr<pcl::PointCloud<pcl::PointXYZI>> POINTCLOUD_XYZI_PTR;
template <class pointT> class KD_TREE;

namespace mins {
struct LiDARData {
LiDARData(double time, double ref_time, int id, boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> pointcloud, double max_range, double min_range);
LiDARData(double time, double ref_time, int id, std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> pointcloud, double max_range, double min_range);

LiDARData();

Expand Down
2 changes: 1 addition & 1 deletion mins/src/update/lidar/UpdaterLidar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ UpdaterLidar::UpdaterLidar(shared_ptr<State> state) : state(state) {
}
}

void UpdaterLidar::feed_measurement(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar) {
void UpdaterLidar::feed_measurement(std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>> lidar) {
// Record first ever measurement time to set up reference time (ref. LidarTypes.h)
FT < 0 ? FT = (double)lidar->header.stamp / 1000 : double();

Expand Down
Loading

0 comments on commit 4e09a0f

Please sign in to comment.