MonoNode.cc
Go to the documentation of this file.
1 #include "MonoNode.h"
2 
3 int main(int argc, char **argv)
4 {
5  ros::init(argc, argv, "Mono");
6  ros::start();
7 
8  if(argc > 1) {
9  ROS_WARN ("Arguments supplied via command line are neglected.");
10  }
11 
12  // Create SLAM system. It initializes all system threads and gets ready to process frames.
13  ros::NodeHandle node_handle;
15 
16  MonoNode node (ORB_SLAM2::System::MONOCULAR, node_handle, image_transport);
17 
18  node.Init();
19 
20  ros::spin();
21 
22  ros::shutdown();
23 
24  return 0;
25 }
26 
27 
28 MonoNode::MonoNode (ORB_SLAM2::System::eSensor sensor, ros::NodeHandle &node_handle, image_transport::ImageTransport &image_transport) : Node (sensor, node_handle, image_transport) {
29  image_subscriber = image_transport.subscribe ("/camera/image_raw", 1, &MonoNode::ImageCallback, this);
30  camera_info_topic_ = "/camera/camera_info";
31 }
32 
33 
35 }
36 
37 
38 void MonoNode::ImageCallback (const sensor_msgs::ImageConstPtr& msg) {
40  try {
41  cv_in_ptr = cv_bridge::toCvShare(msg);
42  } catch (cv_bridge::Exception& e) {
43  ROS_ERROR("cv_bridge exception: %s", e.what());
44  return;
45  }
46 
47  current_frame_time_ = msg->header.stamp;
48 
49  orb_slam_->TrackMonocular(cv_in_ptr->image,cv_in_ptr->header.stamp.toSec());
50 
51  Update ();
52 }
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string camera_info_topic_
Definition: Node.h:66
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void start()
Definition: Node.h:54
void TrackMonocular(const cv::Mat &im, const double &timestamp)
Definition: System.cc:227
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ORB_SLAM2::System * orb_slam_
Definition: Node.h:63
#define ROS_WARN(...)
ROSCPP_DECL void spin(Spinner &spinner)
~MonoNode()
Definition: MonoNode.cc:34
ros::Time current_frame_time_
Definition: Node.h:64
void Init()
Definition: Node.cc:23
void ImageCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: MonoNode.cc:38
int main(int argc, char **argv)
Definition: MonoNode.cc:3
image_transport::Subscriber image_subscriber
Definition: MonoNode.h:48
ROSCPP_DECL void shutdown()
void Update()
Definition: Node.cc:66
MonoNode(const ORB_SLAM2::System::eSensor sensor, ros::NodeHandle &node_handle, image_transport::ImageTransport &image_transport)
Definition: MonoNode.cc:28
#define ROS_ERROR(...)


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05