Skip to content

Commit

Permalink
PCD save enabled
Browse files Browse the repository at this point in the history
  • Loading branch information
ivvi333 authored May 2, 2024
1 parent 93d55b2 commit b364263
Showing 1 changed file with 1 addition and 3 deletions.
4 changes: 1 addition & 3 deletions src/laserMapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -513,7 +513,6 @@ void publish_frame_world(rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::Share
/**************** save map ****************/
/* 1. make sure you have enough memories
/* 2. noted that pcd save will influence the real-time performences **/
/*
if (pcd_save_en)
{
int size = feats_undistort->points.size();
Expand All @@ -540,7 +539,6 @@ void publish_frame_world(rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::Share
scan_wait_num = 0;
}
}
*/
}

void publish_frame_body(rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pubLaserCloudFull_body)
Expand Down Expand Up @@ -1194,4 +1192,4 @@ int main(int argc, char** argv)
}

return 0;
}
}

0 comments on commit b364263

Please sign in to comment.