ros_mono.cc 2.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #include<iostream>
  19. #include<algorithm>
  20. #include<fstream>
  21. #include<chrono>
  22. #include<ros/ros.h>
  23. #include <cv_bridge/cv_bridge.h>
  24. #include<opencv2/core/core.hpp>
  25. #include"../../../include/System.h"
  26. using namespace std;
  27. class ImageGrabber
  28. {
  29. public:
  30. ImageGrabber(ORB_SLAM2::System* pSLAM):mpSLAM(pSLAM){}
  31. void GrabImage(const sensor_msgs::ImageConstPtr& msg);
  32. ORB_SLAM2::System* mpSLAM;
  33. };
  34. int main(int argc, char **argv)
  35. {
  36. ros::init(argc, argv, "Mono");
  37. ros::start();
  38. if(argc != 3)
  39. {
  40. cerr << endl << "Usage: rosrun ORB_SLAM2 Mono path_to_vocabulary path_to_settings" << endl;
  41. ros::shutdown();
  42. return 1;
  43. }
  44. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  45. ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true);
  46. ImageGrabber igb(&SLAM);
  47. ros::NodeHandle nodeHandler;
  48. ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb);
  49. ros::spin();
  50. // Stop all threads
  51. SLAM.Shutdown();
  52. // Save camera trajectory
  53. SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
  54. ros::shutdown();
  55. return 0;
  56. }
  57. void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg)
  58. {
  59. // Copy the ros image message to cv::Mat.
  60. cv_bridge::CvImageConstPtr cv_ptr;
  61. try
  62. {
  63. cv_ptr = cv_bridge::toCvShare(msg);
  64. }
  65. catch (cv_bridge::Exception& e)
  66. {
  67. ROS_ERROR("cv_bridge exception: %s", e.what());
  68. return;
  69. }
  70. mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec());
  71. }