NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
live_measurement_simulator.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 #ifndef LOCALIZATION_ANALYSIS_LIVE_MEASUREMENT_SIMULATOR_H_
20 #define LOCALIZATION_ANALYSIS_LIVE_MEASUREMENT_SIMULATOR_H_
21 
23 #include <ff_common/utils.h>
24 #include <ff_msgs/DepthOdometry.h>
25 #include <ff_msgs/Feature2dArray.h>
26 #include <ff_msgs/FlightMode.h>
27 #include <ff_msgs/VisualLandmarks.h>
28 #include <ff_common/ff_names.h>
35 
36 #include <rosbag/view.h>
37 #include <sensor_msgs/Image.h>
38 #include <sensor_msgs/Imu.h>
39 
40 #include <map>
41 #include <string>
42 #include <utility>
43 
44 namespace localization_analysis {
45 // Buffers sensor messages and passes them to the localizer or VIO once the simulated delay for each message has
46 // passed. Creates optical flow and sparse mapping msgs from image msgs if desired.
48  public:
50 
51  bool ProcessMessage();
52 
54 
55  boost::optional<sensor_msgs::ImageConstPtr> GetImageMessage(const localization_common::Time current_time);
56  boost::optional<sensor_msgs::Imu> GetImuMessage(const localization_common::Time current_time);
57  boost::optional<ff_msgs::Feature2dArray> GetOFMessage(const localization_common::Time current_time);
58  boost::optional<ff_msgs::DepthOdometry> GetDepthOdometryMessage(const localization_common::Time current_time);
59  boost::optional<ff_msgs::VisualLandmarks> GetVLMessage(const localization_common::Time current_time);
60  boost::optional<ff_msgs::VisualLandmarks> GetARMessage(const localization_common::Time current_time);
61  boost::optional<ff_msgs::FlightMode> GetFlightModeMessage(const localization_common::Time current_time);
62 
63  private:
64  ff_msgs::Feature2dArray GenerateOFFeatures(const sensor_msgs::ImageConstPtr& image_msg);
65 
66  bool GenerateVLFeatures(const sensor_msgs::ImageConstPtr& image_msg, ff_msgs::VisualLandmarks& vl_features);
67 
68  rosbag::Bag bag_;
70  localization_node::Localizer map_feature_matcher_;
71  depth_odometry::DepthOdometryWrapper depth_odometry_wrapper_;
73  lk_optical_flow::LKOpticalFlow optical_flow_tracker_;
74  const std::string kImageTopic_;
75  std::string topic_localization_depth_image_;
76  std::string topic_localization_depth_cloud_;
77  std::unique_ptr<rosbag::View> view_;
78  boost::optional<rosbag::View::iterator> view_it_;
79  std::map<localization_common::Time, sensor_msgs::ImageConstPtr> img_buffer_;
81  MessageBuffer<ff_msgs::DepthOdometry> depth_odometry_buffer_;
82  MessageBuffer<ff_msgs::FlightMode> flight_mode_buffer_;
86  localization_common::Time current_time_;
87 };
88 } // namespace localization_analysis
89 
90 #endif // LOCALIZATION_ANALYSIS_LIVE_MEASUREMENT_SIMULATOR_H_
lk_optical_flow.h
depth_odometry_wrapper.h
localization_analysis::LiveMeasurementSimulator
Definition: live_measurement_simulator.h:47
localization_analysis::LiveMeasurementSimulator::CurrentTime
localization_common::Time CurrentTime()
Definition: live_measurement_simulator.cc:171
localization_analysis::LiveMeasurementSimulator::ProcessMessage
bool ProcessMessage()
Definition: live_measurement_simulator.cc:113
localization_analysis
Definition: ar_tag_pose_adder.h:29
localization_analysis::LiveMeasurementSimulatorParams
Definition: live_measurement_simulator_params.h:26
localization.h
localization_node::Localizer
Definition: localization.h:45
depth_odometry::DepthOdometryWrapper
Definition: depth_odometry_wrapper.h:39
utils.h
localization_analysis::LiveMeasurementSimulator::GetDepthOdometryMessage
boost::optional< ff_msgs::DepthOdometry > GetDepthOdometryMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:182
localization_analysis::LiveMeasurementSimulator::GetARMessage
boost::optional< ff_msgs::VisualLandmarks > GetARMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:188
time.h
localization_analysis::LiveMeasurementSimulator::GetOFMessage
boost::optional< ff_msgs::Feature2dArray > GetOFMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:179
ff_names.h
localization_analysis::LiveMeasurementSimulator::LiveMeasurementSimulator
LiveMeasurementSimulator(const LiveMeasurementSimulatorParams &params)
Definition: live_measurement_simulator.cc:29
localization_analysis::MessageBuffer< sensor_msgs::Imu >
localization_analysis::LiveMeasurementSimulator::GetFlightModeMessage
boost::optional< ff_msgs::FlightMode > GetFlightModeMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:176
sparse_map.h
localization_analysis::LiveMeasurementSimulator::GetImuMessage
boost::optional< sensor_msgs::Imu > GetImuMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:173
live_measurement_simulator_params.h
sparse_mapping::SparseMap
Definition: sparse_map.h:63
localization_common::Time
double Time
Definition: time.h:23
localization_analysis::LiveMeasurementSimulator::GetVLMessage
boost::optional< ff_msgs::VisualLandmarks > GetVLMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:185
message_buffer.h
localization_analysis::LiveMeasurementSimulator::GetImageMessage
boost::optional< sensor_msgs::ImageConstPtr > GetImageMessage(const localization_common::Time current_time)
Definition: live_measurement_simulator.cc:191
lk_optical_flow::LKOpticalFlow
Definition: lk_optical_flow.h:36