| Functions | |
| double | getYaw (const tf2::Quaternion quat) | 
| 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) | 
| Method for safely obtaining transforms. | |
| bool | lookupTransformSafe (const tf2_ros::Buffer &buffer, const std::string &targetFrame, const std::string &sourceFrame, const ros::Time &time, tf2::Transform &targetFrameTrans) | 
| Method for safely obtaining transforms. | |
| void | quatToRPY (const tf2::Quaternion &quat, double &roll, double &pitch, double &yaw) | 
| Utility method for converting quaternion to RPY. | |
| void | stateToTF (const Eigen::VectorXd &state, tf2::Transform &stateTF) | 
| Converts our Eigen state vector into a TF transform/pose. | |
| void | TFtoState (const tf2::Transform &stateTF, Eigen::VectorXd &state) | 
| Converts a TF transform/pose into our Eigen state vector. | |
| double RobotLocalization::RosFilterUtilities::getYaw | ( | const tf2::Quaternion | quat | ) | 
Definition at line 86 of file ros_filter_utilities.cpp.
| bool RobotLocalization::RosFilterUtilities::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 | ||
| ) | 
Method for safely obtaining transforms.
| [in] | buffer | - tf buffer object to use for looking up the transform | 
| [in] | targetFrame | - The target frame of the desired transform | 
| [in] | sourceFrame | - The source frame of the desired transform | 
| [in] | time | - The time at which we want the transform | 
| [in] | timeout | - How long to block before falling back to last transform | 
| [out] | targetFrameTrans | - The resulting transform object | 
targetFrameTrans and returns true if successful, false otherwise.This method attempts to obtain a transform from the sourceFrame to the targetFrame at the specific time. If no transform is available at that time, it attempts to simply obtain the latest transform. If that still fails, then the method checks to see if the transform is going from a given frame_id to itself. If any of these checks succeed, the method sets the value of targetFrameTrans and returns true, otherwise it returns false. 
Definition at line 97 of file ros_filter_utilities.cpp.
| bool RobotLocalization::RosFilterUtilities::lookupTransformSafe | ( | const tf2_ros::Buffer & | buffer, | 
| const std::string & | targetFrame, | ||
| const std::string & | sourceFrame, | ||
| const ros::Time & | time, | ||
| tf2::Transform & | targetFrameTrans | ||
| ) | 
Method for safely obtaining transforms.
| [in] | buffer | - tf buffer object to use for looking up the transform | 
| [in] | targetFrame | - The target frame of the desired transform | 
| [in] | sourceFrame | - The source frame of the desired transform | 
| [in] | time | - The time at which we want the transform | 
| [out] | targetFrameTrans | - The resulting transform object | 
targetFrameTrans and returns true if successful, false otherwise.This method attempts to obtain a transform from the sourceFrame to the targetFrame at the specific time. If no transform is available at that time, it attempts to simply obtain the latest transform. If that still fails, then the method checks to see if the transform is going from a given frame_id to itself. If any of these checks succeed, the method sets the value of targetFrameTrans and returns true, otherwise it returns false. 
Definition at line 149 of file ros_filter_utilities.cpp.
| void RobotLocalization::RosFilterUtilities::quatToRPY | ( | const tf2::Quaternion & | quat, | 
| double & | roll, | ||
| double & | pitch, | ||
| double & | yaw | ||
| ) | 
Utility method for converting quaternion to RPY.
| [in] | quat | - The quaternion to convert | 
| [out] | roll | - The converted roll | 
| [out] | pitch | - The converted pitch | 
| [out] | yaw | - The converted yaw | 
Definition at line 158 of file ros_filter_utilities.cpp.
| void RobotLocalization::RosFilterUtilities::stateToTF | ( | const Eigen::VectorXd & | state, | 
| tf2::Transform & | stateTF | ||
| ) | 
Converts our Eigen state vector into a TF transform/pose.
| [in] | state | - The state to convert | 
| [out] | stateTF | - The converted state | 
Definition at line 164 of file ros_filter_utilities.cpp.
| void RobotLocalization::RosFilterUtilities::TFtoState | ( | const tf2::Transform & | stateTF, | 
| Eigen::VectorXd & | state | ||
| ) | 
Converts a TF transform/pose into our Eigen state vector.
| [in] | stateTF | - The state to convert | 
| [out] | state | - The converted state | 
Definition at line 177 of file ros_filter_utilities.cpp.