18 #ifndef DEPTH_ODOMETRY_DEPTH_ODOMETRY_WRAPPER_H_
19 #define DEPTH_ODOMETRY_DEPTH_ODOMETRY_WRAPPER_H_
23 #include <ff_msgs/DepthOdometry.h>
28 #include <pcl/point_cloud.h>
29 #include <pcl/point_types.h>
31 #include <image_transport/image_transport.h>
33 #include <sensor_msgs/PointCloud2.h>
43 std::vector<ff_msgs::DepthOdometry>
PointCloudCallback(
const sensor_msgs::PointCloud2ConstPtr& point_cloud_msg);
44 std::vector<ff_msgs::DepthOdometry>
ImageCallback(
const sensor_msgs::ImageConstPtr& image_msg);
48 std::vector<ff_msgs::DepthOdometry> ProcessDepthImageIfAvailable();
49 std::unique_ptr<DepthOdometry> depth_odometry_;
57 #endif // DEPTH_ODOMETRY_DEPTH_ODOMETRY_WRAPPER_H_