12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394 |
- #include<iostream>
- #include<algorithm>
- #include<fstream>
- #include<chrono>
- #include<ros/ros.h>
- #include <cv_bridge/cv_bridge.h>
- #include<opencv2/core/core.hpp>
- #include"../../../include/System.h"
- using namespace std;
- class ImageGrabber
- {
- public:
- ImageGrabber(ORB_SLAM2::System* pSLAM):mpSLAM(pSLAM){}
- void GrabImage(const sensor_msgs::ImageConstPtr& msg);
- ORB_SLAM2::System* mpSLAM;
- };
- int main(int argc, char **argv)
- {
- ros::init(argc, argv, "Mono");
- ros::start();
- if(argc != 3)
- {
- cerr << endl << "Usage: rosrun ORB_SLAM2 Mono path_to_vocabulary path_to_settings" << endl;
- ros::shutdown();
- return 1;
- }
-
- ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true);
- ImageGrabber igb(&SLAM);
- ros::NodeHandle nodeHandler;
- ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb);
- ros::spin();
-
- SLAM.Shutdown();
-
- SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
- ros::shutdown();
- return 0;
- }
- void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg)
- {
-
- cv_bridge::CvImageConstPtr cv_ptr;
- try
- {
- cv_ptr = cv_bridge::toCvShare(msg);
- }
- catch (cv_bridge::Exception& e)
- {
- ROS_ERROR("cv_bridge exception: %s", e.what());
- return;
- }
- mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec());
- }
|