Skip to content

Commit

Permalink
Use shared_ptr (stella-cv#79)
Browse files Browse the repository at this point in the history
  • Loading branch information
ymd-stella authored Dec 31, 2021
1 parent fd2dc3f commit 39aa232
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions src/openvslam_ros.cc
Original file line number Diff line number Diff line change
Expand Up @@ -72,8 +72,8 @@ void system::publish_pose(const Eigen::Matrix4d& cam_pose_wc, const ros::Time& s
}

void system::publish_pointcloud(const ros::Time& stamp) {
std::vector<openvslam::data::landmark*> landmarks;
std::set<openvslam::data::landmark*> local_landmarks;
std::vector<std::shared_ptr<openvslam::data::landmark>> landmarks;
std::set<std::shared_ptr<openvslam::data::landmark>> local_landmarks;
SLAM_.get_map_publisher()->get_landmarks(landmarks, local_landmarks);
pcl::PointCloud<pcl::PointXYZ> points;
for (const auto lm : landmarks) {
Expand All @@ -98,7 +98,7 @@ void system::publish_keyframes(const ros::Time& stamp) {
keyframes_msg.header.stamp = stamp;
keyframes_msg.header.frame_id = map_frame_;
keyframes_2d_msg.header = keyframes_msg.header;
std::vector<openvslam::data::keyframe*> all_keyfrms;
std::vector<std::shared_ptr<openvslam::data::keyframe>> all_keyfrms;
SLAM_.get_map_publisher()->get_keyframes(all_keyfrms);
for (const auto keyfrm : all_keyfrms) {
if (!keyfrm || keyfrm->will_be_erased()) {
Expand Down

0 comments on commit 39aa232

Please sign in to comment.