ros_filter_utilities.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  * 3. Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived
17  * from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
33 #ifndef ROBOT_LOCALIZATION_ROS_FILTER_UTILITIES_H
34 #define ROBOT_LOCALIZATION_ROS_FILTER_UTILITIES_H
35 
38 #include <tf2_ros/buffer.h>
39 
40 #include <Eigen/Dense>
41 
42 #include <iomanip>
43 #include <iostream>
44 #include <string>
45 #include <vector>
46 
47 #define RF_DEBUG(msg) if (filter_.getDebug()) { debugStream_ << msg; }
48 
49 // Handy methods for debug output
50 std::ostream& operator<<(std::ostream& os, const tf2::Vector3 &vec);
51 std::ostream& operator<<(std::ostream& os, const tf2::Quaternion &quat);
52 std::ostream& operator<<(std::ostream& os, const tf2::Transform &trans);
53 std::ostream& operator<<(std::ostream& os, const std::vector<double> &vec);
54 
55 namespace RobotLocalization
56 {
57 namespace RosFilterUtilities
58 {
59 
60 double getYaw(const tf2::Quaternion quat);
61 
80 bool lookupTransformSafe(const tf2_ros::Buffer &buffer,
81  const std::string &targetFrame,
82  const std::string &sourceFrame,
83  const ros::Time &time,
84  const ros::Duration &timeout,
85  tf2::Transform &targetFrameTrans,
86  const bool silent = false);
87 
105 bool lookupTransformSafe(const tf2_ros::Buffer &buffer,
106  const std::string &targetFrame,
107  const std::string &sourceFrame,
108  const ros::Time &time,
109  tf2::Transform &targetFrameTrans,
110  const bool silent = false);
111 
118 void quatToRPY(const tf2::Quaternion &quat, double &roll, double &pitch, double &yaw);
119 
124 void stateToTF(const Eigen::VectorXd &state, tf2::Transform &stateTF);
125 
130 void TFtoState(const tf2::Transform &stateTF, Eigen::VectorXd &state);
131 
132 } // namespace RosFilterUtilities
133 } // namespace RobotLocalization
134 
135 #endif // ROBOT_LOCALIZATION_ROS_FILTER_UTILITIES_H
void stateToTF(const Eigen::VectorXd &state, tf2::Transform &stateTF)
Converts our Eigen state vector into a TF transform/pose.
std::ostream & operator<<(std::ostream &os, const tf2::Vector3 &vec)
bool lookupTransformSafe(const tf2_ros::Buffer &buffer, const std::string &targetFrame, const std::string &sourceFrame, const ros::Time &time, const ros::Duration &timeout, tf2::Transform &targetFrameTrans, const bool silent=false)
Method for safely obtaining transforms.
double getYaw(const tf2::Quaternion quat)
void quatToRPY(const tf2::Quaternion &quat, double &roll, double &pitch, double &yaw)
Utility method for converting quaternion to RPY.
void TFtoState(const tf2::Transform &stateTF, Eigen::VectorXd &state)
Converts a TF transform/pose into our Eigen state vector.


robot_localization
Author(s): Tom Moore
autogenerated on Wed Feb 3 2021 03:34:02