3 int main(
int argc,
char **argv)
9 ROS_WARN (
"Arguments supplied via command line are neglected.");
43 ROS_ERROR(
"cv_bridge exception: %s", e.what());
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string camera_info_topic_
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())
void TrackMonocular(const cv::Mat &im, const double ×tamp)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ORB_SLAM2::System * orb_slam_
ROSCPP_DECL void spin(Spinner &spinner)
ros::Time current_frame_time_
void ImageCallback(const sensor_msgs::ImageConstPtr &msg)
int main(int argc, char **argv)
image_transport::Subscriber image_subscriber
ROSCPP_DECL void shutdown()
MonoNode(const ORB_SLAM2::System::eSensor sensor, ros::NodeHandle &node_handle, image_transport::ImageTransport &image_transport)