NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
depth_odometry_wrapper.h
Go to the documentation of this file.
1 /* Copyright (c) 2017, United States Government, as represented by the
2  * Administrator of the National Aeronautics and Space Administration.
3  *
4  * All rights reserved.
5  *
6  * The Astrobee platform is licensed under the Apache License, Version 2.0
7  * (the "License"); you may not use this file except in compliance with the
8  * License. You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15  * License for the specific language governing permissions and limitations
16  * under the License.
17  */
18 #ifndef DEPTH_ODOMETRY_DEPTH_ODOMETRY_WRAPPER_H_
19 #define DEPTH_ODOMETRY_DEPTH_ODOMETRY_WRAPPER_H_
20 
23 #include <ff_msgs/DepthOdometry.h>
27 
28 #include <pcl/point_cloud.h>
29 #include <pcl/point_types.h>
30 
31 #include <image_transport/image_transport.h>
32 
33 #include <sensor_msgs/PointCloud2.h>
34 
35 #include <string>
36 #include <vector>
37 
38 namespace depth_odometry {
40  public:
41  explicit DepthOdometryWrapper(const std::string& path_prefix = "localization/");
42  explicit DepthOdometryWrapper(const DepthOdometryWrapperParams& params);
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);
45 
46  private:
47  void Initialize(const DepthOdometryWrapperParams& params);
48  std::vector<ff_msgs::DepthOdometry> ProcessDepthImageIfAvailable();
49  std::unique_ptr<DepthOdometry> depth_odometry_;
53  localization_common::Timer timer_ = localization_common::Timer("Depth Odometry");
54 };
55 } // namespace depth_odometry
56 
57 #endif // DEPTH_ODOMETRY_DEPTH_ODOMETRY_WRAPPER_H_
localization_common::Timer
Definition: timer.h:30
depth_odometry_wrapper_params.h
depth_odometry
Definition: depth_image_features_and_points.h:34
depth_odometry::DepthOdometryWrapper
Definition: depth_odometry_wrapper.h:39
timestamped_set.h
localization_common::TimestampedSet< sensor_msgs::PointCloud2ConstPtr >
timer.h
time.h
depth_odometry.h
depth_odometry::DepthOdometryWrapper::ImageCallback
std::vector< ff_msgs::DepthOdometry > ImageCallback(const sensor_msgs::ImageConstPtr &image_msg)
Definition: depth_odometry_wrapper.cc:72
depth_odometry::DepthOdometryWrapper::PointCloudCallback
std::vector< ff_msgs::DepthOdometry > PointCloudCallback(const sensor_msgs::PointCloud2ConstPtr &point_cloud_msg)
Definition: depth_odometry_wrapper.cc:66
depth_odometry::DepthOdometryWrapper::DepthOdometryWrapper
DepthOdometryWrapper(const std::string &path_prefix="localization/")
Definition: depth_odometry_wrapper.cc:36
depth_odometry::DepthOdometryWrapperParams
Definition: depth_odometry_wrapper_params.h:29