Skip to content

Commit b92bc19

Browse files
authored
pass by reference the pointclouds (#472)
1 parent 3ac517b commit b92bc19

File tree

2 files changed

+4
-4
lines changed

2 files changed

+4
-4
lines changed

ros/src/OdometryServer.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -191,8 +191,8 @@ void OdometryServer::PublishOdometry(const Sophus::SE3d &kiss_pose,
191191
odom_publisher_->publish(std::move(odom_msg));
192192
}
193193

194-
void OdometryServer::PublishClouds(const std::vector<Eigen::Vector3d> frame,
195-
const std::vector<Eigen::Vector3d> keypoints,
194+
void OdometryServer::PublishClouds(const std::vector<Eigen::Vector3d> &frame,
195+
const std::vector<Eigen::Vector3d> &keypoints,
196196
const std_msgs::msg::Header &header) {
197197
const auto kiss_map = kiss_icp_->LocalMap();
198198
const auto kiss_pose = kiss_icp_->pose().inverse();

ros/src/OdometryServer.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -52,8 +52,8 @@ class OdometryServer : public rclcpp::Node {
5252
void PublishOdometry(const Sophus::SE3d &kiss_pose, const std_msgs::msg::Header &header);
5353

5454
/// Stream the debugging point clouds for visualization (if required)
55-
void PublishClouds(const std::vector<Eigen::Vector3d> frame,
56-
const std::vector<Eigen::Vector3d> keypoints,
55+
void PublishClouds(const std::vector<Eigen::Vector3d> &frame,
56+
const std::vector<Eigen::Vector3d> &keypoints,
5757
const std_msgs::msg::Header &header);
5858

5959
private:

0 commit comments

Comments
 (0)