Skip to content

Commit

Permalink
Merge pull request #191 from AchmadFathoni/master
Browse files Browse the repository at this point in the history
Successfully compile to pcl-1.11.1, pcl-ros-1.7.2 and g20-20201223_git
  • Loading branch information
koide3 authored Jun 10, 2021
2 parents 9fd7c27 + 52a7801 commit 31ed9d6
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 7 deletions.
4 changes: 2 additions & 2 deletions apps/floor_detection_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ class FloorDetectionNodelet : public nodelet::Nodelet {

if(floor_filtered_pub.getNumSubscribers()) {
filtered->header = cloud->header;
floor_filtered_pub.publish(filtered);
floor_filtered_pub.publish(*filtered);
}

// too few points for RANSAC
Expand Down Expand Up @@ -171,7 +171,7 @@ class FloorDetectionNodelet : public nodelet::Nodelet {
extract.filter(*inlier_cloud);
inlier_cloud->header = cloud->header;

floor_points_pub.publish(inlier_cloud);
floor_points_pub.publish(*inlier_cloud);
}

return Eigen::Vector4f(coeffs);
Expand Down
7 changes: 4 additions & 3 deletions apps/prefiltering_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,8 @@ class PrefilteringNodelet : public nodelet::Nodelet {
imu_queue.push_back(imu_msg);
}

void cloud_callback(pcl::PointCloud<PointT>::ConstPtr src_cloud) {
void cloud_callback(const pcl::PointCloud<PointT>& src_cloud_r) {
pcl::PointCloud<PointT>::ConstPtr src_cloud = src_cloud_r.makeShared();
if(src_cloud->empty()) {
return;
}
Expand Down Expand Up @@ -131,7 +132,7 @@ class PrefilteringNodelet : public nodelet::Nodelet {
filtered = downsample(filtered);
filtered = outlier_removal(filtered);

points_pub.publish(filtered);
points_pub.publish(*filtered);
}

pcl::PointCloud<PointT>::ConstPtr downsample(const pcl::PointCloud<PointT>::ConstPtr& cloud) const {
Expand Down Expand Up @@ -200,7 +201,7 @@ class PrefilteringNodelet : public nodelet::Nodelet {
colored->at(i).g = 128;
colored->at(i).b = 255 * (1 - t);
}
colored_pub.publish(colored);
colored_pub.publish(*colored);
}

sensor_msgs::ImuConstPtr imu_msg = imu_queue.front();
Expand Down
2 changes: 1 addition & 1 deletion apps/scan_matching_odometry_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,7 @@ class ScanMatchingOdometryNodelet : public nodelet::Nodelet {
{
pcl::transformPointCloud (*cloud, *aligned, odom);
aligned->header.frame_id=odom_frame_id;
aligned_points_pub.publish(aligned);
aligned_points_pub.publish(*aligned);
}

return odom;
Expand Down
2 changes: 1 addition & 1 deletion src/hdl_graph_slam/graph_slam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -334,7 +334,7 @@ bool GraphSLAM::load(const std::string& filename) {
g2o::SparseOptimizer* graph = dynamic_cast<g2o::SparseOptimizer*>(this->graph.get());

std::ifstream ifs(filename);
if(!graph->load(ifs, true)) {
if(!graph->load(ifs)) {
return false;
}

Expand Down

0 comments on commit 31ed9d6

Please sign in to comment.