#include <gtest/gtest.h>
#include <tf/tf.h>
#include <sys/time.h>
#include <ros/ros.h>
#include "tf/LinearMath/Vector3.h"
#include "rostest/permuter.h"
Go to the source code of this file.
Defines | |
#define | CHECK_QUATERNION_NEAR(_q1, _q2, _epsilon) EXPECT_NEAR(_q1.angle(_q2), 0, _epsilon); \ |
#define | CHECK_TRANSFORMS_NEAR(_out, _expected, _eps) |
Functions | |
bool | expectInvalidQuaternion (tf::Quaternion q) |
bool | expectInvalidQuaternion (geometry_msgs::Quaternion q) |
bool | expectValidQuaternion (tf::Quaternion q) |
bool | expectValidQuaternion (geometry_msgs::Quaternion q) |
void | generate_rand_vectors (double scale, uint64_t runs, std::vector< double > &xvalues, std::vector< double > &yvalues, std::vector< double > &zvalues) |
int | main (int argc, char **argv) |
void | push_back_1 (std::vector< std::string > &children, std::vector< std::string > &parents, std::vector< double > &dx, std::vector< double > &dy) |
void | push_back_i (std::vector< std::string > &children, std::vector< std::string > &parents, std::vector< double > &dx, std::vector< double > &dy) |
void | push_back_v (std::vector< std::string > &children, std::vector< std::string > &parents, std::vector< double > &dx, std::vector< double > &dy) |
void | push_back_y (std::vector< std::string > &children, std::vector< std::string > &parents, std::vector< double > &dx, std::vector< double > &dy) |
void | seed_rand () |
void | setupTree (tf::Transformer &mTR, const std::string &mode, const ros::Time &time, const ros::Duration &interpolation_space=ros::Duration()) |
TEST (tf, lookupTransform_compount) | |
TEST (tf, lookupTransform_helix_configuration) | |
TEST (tf, lookupTransform_ring45) | |
TEST (tf, setTransformNoInsertOnSelfTransform) | |
TEST (tf, setTransformNoInsertWithNan) | |
TEST (tf, setTransformNoInsertWithNoFrameID) | |
TEST (tf, setTransformNoInsertWithNoParentID) | |
TEST (tf, TransformTransformsCartesian) | |
TEST (tf, TransformTransformToOwnFrame) | |
TEST (tf, TransformPointCartesian) | |
TEST (tf, TransformVectorCartesian) | |
TEST (tf, TransformQuaternionCartesian) | |
TEST (data, Vector3Conversions) | |
TEST (data, Vector3StampedConversions) | |
TEST (data, QuaternionConversions) | |
TEST (data, QuaternionStampedConversions) | |
TEST (data, TransformConversions) | |
TEST (data, PoseStampedConversions) | |
TEST (tf, ListOneInverse) | |
TEST (tf, ListTwoInverse) | |
TEST (tf, ListOneForward) | |
TEST (tf, ListTwoForward) | |
TEST (tf, TransformThrougRoot) | |
TEST (tf, TransformThroughNO_PARENT) | |
TEST (tf, getParent) | |
TEST (tf, NO_PARENT_SET) | |
TEST (tf, waitForTransform) | |
TEST (tf, Exceptions) | |
TEST (tf, NoExtrapolationExceptionFromParent) | |
TEST (tf, ExtrapolationFromOneValue) | |
TEST (tf, RepeatedTimes) | |
TEST (tf, frameExists) | |
TEST (tf, canTransform) | |
TEST (tf, lookupTransform) | |
TEST (tf, getFrameStrings) | |
TEST (tf, assertQuaternionValid) | |
TEST (tf, assertQuaternionMsgValid) | |
TEST (data, StampedOperatorEqualEqual) | |
TEST (data, StampedTransformOperatorEqualEqual) | |
TEST (data, StampedOperatorEqual) |
#define CHECK_QUATERNION_NEAR | ( | _q1, | |
_q2, | |||
_epsilon | |||
) | EXPECT_NEAR(_q1.angle(_q2), 0, _epsilon); \ |
Definition at line 270 of file tf_unittest.cpp.
#define CHECK_TRANSFORMS_NEAR | ( | _out, | |
_expected, | |||
_eps | |||
) |
EXPECT_NEAR(_out.getOrigin().x(), _expected.getOrigin().x(), epsilon); \ EXPECT_NEAR(_out.getOrigin().y(), _expected.getOrigin().y(), epsilon); \ EXPECT_NEAR(_out.getOrigin().z(), _expected.getOrigin().z(), epsilon); \ CHECK_QUATERNION_NEAR(_out.getRotation(), _expected.getRotation(), _eps);
Definition at line 274 of file tf_unittest.cpp.
bool expectInvalidQuaternion | ( | tf::Quaternion | q | ) |
Definition at line 2295 of file tf_unittest.cpp.
bool expectInvalidQuaternion | ( | geometry_msgs::Quaternion | q | ) |
Definition at line 2328 of file tf_unittest.cpp.
bool expectValidQuaternion | ( | tf::Quaternion | q | ) |
Definition at line 2315 of file tf_unittest.cpp.
bool expectValidQuaternion | ( | geometry_msgs::Quaternion | q | ) |
Definition at line 2348 of file tf_unittest.cpp.
void generate_rand_vectors | ( | double | scale, |
uint64_t | runs, | ||
std::vector< double > & | xvalues, | ||
std::vector< double > & | yvalues, | ||
std::vector< double > & | zvalues | ||
) |
Definition at line 49 of file tf_unittest.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 2524 of file tf_unittest.cpp.
void push_back_1 | ( | std::vector< std::string > & | children, |
std::vector< std::string > & | parents, | ||
std::vector< double > & | dx, | ||
std::vector< double > & | dy | ||
) |
Definition at line 148 of file tf_unittest.cpp.
void push_back_i | ( | std::vector< std::string > & | children, |
std::vector< std::string > & | parents, | ||
std::vector< double > & | dx, | ||
std::vector< double > & | dy | ||
) |
Definition at line 61 of file tf_unittest.cpp.
void push_back_v | ( | std::vector< std::string > & | children, |
std::vector< std::string > & | parents, | ||
std::vector< double > & | dx, | ||
std::vector< double > & | dy | ||
) |
Definition at line 115 of file tf_unittest.cpp.
void push_back_y | ( | std::vector< std::string > & | children, |
std::vector< std::string > & | parents, | ||
std::vector< double > & | dx, | ||
std::vector< double > & | dy | ||
) |
Definition at line 83 of file tf_unittest.cpp.
void seed_rand | ( | ) |
Definition at line 41 of file tf_unittest.cpp.
void setupTree | ( | tf::Transformer & | mTR, |
const std::string & | mode, | ||
const ros::Time & | time, | ||
const ros::Duration & | interpolation_space = ros::Duration() |
||
) |
Standard
Definition at line 157 of file tf_unittest.cpp.
TEST | ( | tf | , |
lookupTransform_compount | |||
) |
Definition at line 282 of file tf_unittest.cpp.
TEST | ( | tf | , |
lookupTransform_helix_configuration | |||
) |
Definition at line 406 of file tf_unittest.cpp.
TEST | ( | tf | , |
lookupTransform_ring45 | |||
) |
Definition at line 522 of file tf_unittest.cpp.
TEST | ( | tf | , |
setTransformNoInsertOnSelfTransform | |||
) |
Definition at line 745 of file tf_unittest.cpp.
TEST | ( | tf | , |
setTransformNoInsertWithNan | |||
) |
Definition at line 752 of file tf_unittest.cpp.
TEST | ( | tf | , |
setTransformNoInsertWithNoFrameID | |||
) |
Definition at line 764 of file tf_unittest.cpp.
TEST | ( | tf | , |
setTransformNoInsertWithNoParentID | |||
) |
Definition at line 771 of file tf_unittest.cpp.
TEST | ( | tf | , |
TransformTransformsCartesian | |||
) |
Definition at line 778 of file tf_unittest.cpp.
TEST | ( | tf | , |
TransformTransformToOwnFrame | |||
) |
Make sure that the edge cases of transform the top of the tree to the top of the tree and the leaf of the tree can transform to the leaf of the tree without a lookup exception and accurately
Definition at line 834 of file tf_unittest.cpp.
TEST | ( | tf | , |
TransformPointCartesian | |||
) |
Definition at line 903 of file tf_unittest.cpp.
TEST | ( | tf | , |
TransformVectorCartesian | |||
) |
Definition at line 951 of file tf_unittest.cpp.
TEST | ( | tf | , |
TransformQuaternionCartesian | |||
) |
Definition at line 999 of file tf_unittest.cpp.
TEST | ( | data | , |
Vector3Conversions | |||
) |
Definition at line 1047 of file tf_unittest.cpp.
TEST | ( | data | , |
Vector3StampedConversions | |||
) |
Definition at line 1070 of file tf_unittest.cpp.
TEST | ( | data | , |
QuaternionConversions | |||
) |
Definition at line 1094 of file tf_unittest.cpp.
TEST | ( | data | , |
QuaternionStampedConversions | |||
) |
Definition at line 1119 of file tf_unittest.cpp.
TEST | ( | data | , |
TransformConversions | |||
) |
Definition at line 1145 of file tf_unittest.cpp.
TEST | ( | data | , |
PoseStampedConversions | |||
) |
Definition at line 1176 of file tf_unittest.cpp.
TEST | ( | tf | , |
ListOneInverse | |||
) |
Definition at line 1208 of file tf_unittest.cpp.
TEST | ( | tf | , |
ListTwoInverse | |||
) |
Definition at line 1252 of file tf_unittest.cpp.
TEST | ( | tf | , |
ListOneForward | |||
) |
Definition at line 1299 of file tf_unittest.cpp.
TEST | ( | tf | , |
ListTwoForward | |||
) |
Definition at line 1343 of file tf_unittest.cpp.
TEST | ( | tf | , |
TransformThrougRoot | |||
) |
Definition at line 1389 of file tf_unittest.cpp.
TEST | ( | tf | , |
TransformThroughNO_PARENT | |||
) |
Definition at line 1435 of file tf_unittest.cpp.
TEST | ( | tf | , |
getParent | |||
) |
Definition at line 1482 of file tf_unittest.cpp.
TEST | ( | tf | , |
NO_PARENT_SET | |||
) |
Definition at line 1530 of file tf_unittest.cpp.
TEST | ( | tf | , |
waitForTransform | |||
) |
Definition at line 1563 of file tf_unittest.cpp.
TEST | ( | tf | , |
Exceptions | |||
) |
Definition at line 1619 of file tf_unittest.cpp.
TEST | ( | tf | , |
NoExtrapolationExceptionFromParent | |||
) |
Definition at line 1783 of file tf_unittest.cpp.
TEST | ( | tf | , |
ExtrapolationFromOneValue | |||
) |
Definition at line 1819 of file tf_unittest.cpp.
TEST | ( | tf | , |
RepeatedTimes | |||
) |
Definition at line 1903 of file tf_unittest.cpp.
TEST | ( | tf | , |
frameExists | |||
) |
Definition at line 1931 of file tf_unittest.cpp.
TEST | ( | tf | , |
canTransform | |||
) |
Definition at line 1987 of file tf_unittest.cpp.
TEST | ( | tf | , |
lookupTransform | |||
) |
Definition at line 2085 of file tf_unittest.cpp.
TEST | ( | tf | , |
getFrameStrings | |||
) |
Definition at line 2269 of file tf_unittest.cpp.
TEST | ( | tf | , |
assertQuaternionValid | |||
) |
Definition at line 2362 of file tf_unittest.cpp.
TEST | ( | tf | , |
assertQuaternionMsgValid | |||
) |
Definition at line 2398 of file tf_unittest.cpp.
TEST | ( | data | , |
StampedOperatorEqualEqual | |||
) |
Definition at line 2437 of file tf_unittest.cpp.
TEST | ( | data | , |
StampedTransformOperatorEqualEqual | |||
) |
Definition at line 2464 of file tf_unittest.cpp.
TEST | ( | data | , |
StampedOperatorEqual | |||
) |
Definition at line 2510 of file tf_unittest.cpp.