NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
depth_odometry_display.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 
19 // Header file must go in src directory for Qt/Rviz plugin
20 #ifndef LOCALIZATION_RVIZ_PLUGINS_DEPTH_ODOMETRY_DISPLAY_H_ // NOLINT
21 #define LOCALIZATION_RVIZ_PLUGINS_DEPTH_ODOMETRY_DISPLAY_H_ // NOLINT
22 
23 // Required for Qt
24 #ifndef Q_MOC_RUN
25 #include <QObject>
26 #include <camera/camera_params.h>
27 #include <ff_msgs/DepthOdometry.h>
28 #include <localization_common/measurement_buffer.h>
32 #include <image_transport/image_transport.h>
33 #include <opencv2/core.hpp>
34 #include <pcl/point_cloud.h>
35 #include <pcl/point_types.h>
36 #include <ros/publisher.h>
37 #include <ros/subscriber.h>
38 #include <sensor_msgs/PointCloud2.h>
39 #include <rviz/message_filter_display.h>
40 #include "slider_property.h" // NOLINT
41 #endif
42 
43 // Forward declarations for ogre and rviz
44 namespace Ogre {
45 class SceneNode;
46 }
47 
48 namespace localization_rviz_plugins {
49 class DepthOdometryDisplay : public rviz::MessageFilterDisplay<ff_msgs::DepthOdometry> {
50  Q_OBJECT // NOLINT
51  public : // NOLINT
53  ~DepthOdometryDisplay() = default;
54 
55  // private:
56  protected:
57  void onInitialize() final;
58  void reset() final;
59 
60  private Q_SLOTS: // NOLINT
61  void createSingleCorrespondenceDisplays();
62 
63  private:
64  void processMessage(const ff_msgs::DepthOdometry::ConstPtr& depth_odometry_msg);
65  void createProjectionAndOpticalFlowImage(const localization_measurements::DepthOdometryMeasurement& depth_odometry);
66  cv::Point2f projectPoint(const Eigen::Vector3d& point_3d);
67  void imageCallback(const sensor_msgs::ImageConstPtr& image_msg);
68  void pointCloudCallback(const sensor_msgs::PointCloud2ConstPtr& point_cloud_msg);
69  void publishCorrespondencePoints(const Eigen::Vector3d& source_3d_point, const Eigen::Vector3d& target_3d_point,
70  const localization_common::Time source_time,
71  const localization_common::Time target_time);
72  void clearDisplay();
73 
74  std::unique_ptr<camera::CameraParameters> camera_params_;
75  std::unique_ptr<rviz::SliderProperty> correspondence_index_slider_;
76  cv::Mat intrinsics_;
77  cv::Mat distortion_params_;
78  image_transport::Subscriber image_sub_;
79  ros::Subscriber point_cloud_sub_;
80  ros::Publisher source_correspondence_point_pub_, target_correspondence_point_pub_;
81  ros::Publisher source_point_cloud_pub_, target_point_cloud_pub_;
82  image_transport::Publisher single_correspondence_image_pub_, projection_and_optical_flow_image_pub_;
83  ros::NodeHandle nh_;
84  localization_common::MeasurementBuffer<sensor_msgs::ImageConstPtr> img_buffer_;
85  localization_common::MeasurementBuffer<pcl::PointCloud<pcl::PointXYZ>::Ptr> point_cloud_buffer_;
86  boost::optional<localization_measurements::DepthOdometryMeasurement> latest_depth_odometry_measurement_;
87 };
88 } // namespace localization_rviz_plugins
89 #endif // LOCALIZATION_RVIZ_PLUGINS_DEPTH_ODOMETRY_DISPLAY_H_ NOLINT
depth_odometry_measurement.h
localization_rviz_plugins::DepthOdometryDisplay::DepthOdometryDisplay
DepthOdometryDisplay()
Definition: depth_odometry_display.cc:49
localization_rviz_plugins::DepthOdometryDisplay::reset
void reset() final
Definition: depth_odometry_display.cc:102
Ogre
Definition: trajectory_display.h:28
depth_odometry
Definition: depth_image_features_and_points.h:34
localization_rviz_plugins::DepthOdometryDisplay
Definition: depth_odometry_display.h:49
point_cloud_common::Vector3d
Eigen::Vector3d Vector3d(const PointType &point)
Definition: utilities.h:328
time.h
localization_rviz_plugins::DepthOdometryDisplay::onInitialize
void onInitialize() final
Definition: depth_odometry_display.cc:100
slider_property.h
localization_measurements::DepthOdometryMeasurement
Definition: depth_odometry_measurement.h:28
localization_rviz_plugins::DepthOdometryDisplay::~DepthOdometryDisplay
~DepthOdometryDisplay()=default
localization_rviz_plugins
Definition: depth_odometry_display.cc:42
measurement_conversions.h
localization_common::Time
double Time
Definition: time.h:23
camera_params.h