NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
utilities.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 LOCALIZATION_ANALYSIS_UTILITIES_H_
19 #define LOCALIZATION_ANALYSIS_UTILITIES_H_
20 
21 #include <camera/camera_params.h>
26 
27 #include <opencv2/core/mat.hpp>
28 
29 #include <rosbag/bag.h>
30 #include <sensor_msgs/Image.h>
31 
32 #include <string>
33 #include <vector>
34 
35 namespace localization_analysis {
36 bool string_ends_with(const std::string& str, const std::string& ending);
37 
38 template <typename MsgType>
39 void SaveMsg(const MsgType& msg, const std::string& topic, rosbag::Bag& bag) {
40  const ros::Time timestamp = localization_common::RosTimeFromHeader(msg.header);
41  bag.write("/" + topic, timestamp, msg);
42 }
43 
44 geometry_msgs::PoseStamped PoseMsg(const Eigen::Isometry3d& global_T_body, const std_msgs::Header& header);
45 
46 geometry_msgs::PoseStamped PoseMsg(const Eigen::Isometry3d& global_T_body, const localization_common::Time time);
47 
48 geometry_msgs::PoseStamped PoseMsg(const gtsam::Pose3& global_T_body, const localization_common::Time time);
49 
50 geometry_msgs::PoseStamped PoseMsg(const localization_measurements::TimestampedPose& timestamped_pose);
51 } // namespace localization_analysis
52 
53 #endif // LOCALIZATION_ANALYSIS_UTILITIES_H_
localization_analysis
Definition: ar_tag_pose_adder.h:29
utilities.h
vision_common::Isometry3d
Eigen::Isometry3d Isometry3d(const cv::Mat &rodrigues_rotation_cv, const cv::Mat &translation_cv)
Definition: utilities.cc:58
localization_analysis::string_ends_with
bool string_ends_with(const std::string &str, const std::string &ending)
Definition: utilities.cc:117
graph_localizer.h
localization_analysis::SaveMsg
void SaveMsg(const MsgType &msg, const std::string &topic, rosbag::Bag &bag)
Definition: utilities.h:39
timestamped_pose.h
feature_tracker.h
localization_analysis::PoseMsg
geometry_msgs::PoseStamped PoseMsg(const Eigen::Isometry3d &global_T_body, const std_msgs::Header &header)
Definition: utilities.cc:125
localization_measurements::TimestampedPose
Definition: timestamped_pose.h:27
localization_common::RosTimeFromHeader
ros::Time RosTimeFromHeader(const std_msgs::Header &header)
Definition: utilities.cc:107
localization_common::Time
double Time
Definition: time.h:23
camera_params.h