Classes | Macros | Functions
buffer_core_test.cpp File Reference
#include <cmath>
#include <gtest/gtest.h>
#include <tf2/buffer_core.h>
#include "tf2/exceptions.h"
#include <ros/ros.h>
#include "LinearMath/btVector3.h"
#include "LinearMath/btTransform.h"
#include "rostest/permuter.h"
Include dependency graph for buffer_core_test.cpp:

Go to the source code of this file.

Classes

struct  TransformableHelper
 

Macros

#define CHECK_QUATERNION_NEAR(_q1, _x, _y, _z, _w, _epsilon)
 
#define CHECK_TRANSFORMS_NEAR(_out, _expected, _eps)
 

Functions

bool check_1_result (const geometry_msgs::TransformStamped &outpose, const std::string &source_frame, const std::string &target_frame, const ros::Time &eval_time, double epsilon)
 
bool check_v_result (const geometry_msgs::TransformStamped &outpose, const std::string &source_frame, const std::string &target_frame, const ros::Time &eval_time, double epsilon)
 
bool check_y_result (const geometry_msgs::TransformStamped &outpose, const std::string &source_frame, const std::string &target_frame, const ros::Time &eval_time, double epsilon)
 
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 setIdentity (geometry_msgs::Transform &trans)
 
void setupTree (tf2::BufferCore &mBC, const std::string &mode, const ros::Time &time, const ros::Duration &interpolation_space=ros::Duration())
 
 TEST (BufferCore_canTransform, invalid_arguments)
 
 TEST (BufferCore_lookupTransform, compound_xfm_configuration)
 
 TEST (BufferCore_lookupTransform, helix_configuration)
 
 TEST (BufferCore_lookupTransform, i_configuration)
 
 TEST (BufferCore_lookupTransform, invalid_arguments)
 
 TEST (BufferCore_lookupTransform, multi_configuration)
 
 TEST (BufferCore_lookupTransform, one_link_configuration)
 
 TEST (BufferCore_lookupTransform, ring_45_configuration)
 
 TEST (BufferCore_lookupTransform, v_configuration)
 
 TEST (BufferCore_lookupTransform, y_configuration)
 
 TEST (BufferCore_setTransform, NoInsertOnSelfTransform)
 
 TEST (BufferCore_setTransform, NoInsertWithNan)
 
 TEST (BufferCore_setTransform, NoInsertWithNoFrameID)
 
 TEST (BufferCore_setTransform, NoInsertWithNoParentID)
 
 TEST (BufferCore_transformableCallbacks, alreadyTransformable)
 
 TEST (BufferCore_transformableCallbacks, waitForNewTransform)
 
 TEST (BufferCore_transformableCallbacks, waitForOldTransform)
 

Macro Definition Documentation

◆ CHECK_QUATERNION_NEAR

#define CHECK_QUATERNION_NEAR (   _q1,
  _x,
  _y,
  _z,
  _w,
  _epsilon 
)
Value:
{ \
btQuaternion q1(_q1.x, _q1.y, _q1.z, _q1.w); \
btQuaternion q2(_x, _y, _z, _w); \
double angle = q1.angle(q2); \
EXPECT_TRUE(fabs(angle) < _epsilon || fabs(angle - M_PI) < _epsilon); \
}

Definition at line 1143 of file buffer_core_test.cpp.

◆ CHECK_TRANSFORMS_NEAR

#define CHECK_TRANSFORMS_NEAR (   _out,
  _expected,
  _eps 
)
Value:
EXPECT_NEAR(_out.transform.translation.x, _expected.getOrigin().x(), epsilon); \
EXPECT_NEAR(_out.transform.translation.y, _expected.getOrigin().y(), epsilon); \
EXPECT_NEAR(_out.transform.translation.z, _expected.getOrigin().z(), epsilon); \
CHECK_QUATERNION_NEAR(_out.transform.rotation, _expected.getRotation().x(), _expected.getRotation().y(), _expected.getRotation().z(), _expected.getRotation().w(), _eps);

Definition at line 1151 of file buffer_core_test.cpp.

Function Documentation

◆ check_1_result()

bool check_1_result ( const geometry_msgs::TransformStamped &  outpose,
const std::string &  source_frame,
const std::string &  target_frame,
const ros::Time eval_time,
double  epsilon 
)

Definition at line 686 of file buffer_core_test.cpp.

◆ check_v_result()

bool check_v_result ( const geometry_msgs::TransformStamped &  outpose,
const std::string &  source_frame,
const std::string &  target_frame,
const ros::Time eval_time,
double  epsilon 
)

Definition at line 721 of file buffer_core_test.cpp.

◆ check_y_result()

bool check_y_result ( const geometry_msgs::TransformStamped &  outpose,
const std::string &  source_frame,
const std::string &  target_frame,
const ros::Time eval_time,
double  epsilon 
)

Definition at line 831 of file buffer_core_test.cpp.

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 2793 of file buffer_core_test.cpp.

◆ push_back_1()

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 138 of file buffer_core_test.cpp.

◆ push_back_i()

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 51 of file buffer_core_test.cpp.

◆ push_back_v()

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 105 of file buffer_core_test.cpp.

◆ push_back_y()

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 73 of file buffer_core_test.cpp.

◆ setIdentity()

void setIdentity ( geometry_msgs::Transform &  trans)

Definition at line 39 of file buffer_core_test.cpp.

◆ setupTree()

void setupTree ( tf2::BufferCore mBC,
const std::string &  mode,
const ros::Time time,
const ros::Duration interpolation_space = ros::Duration() 
)

Standard

Definition at line 147 of file buffer_core_test.cpp.

◆ TEST() [1/17]

TEST ( BufferCore_canTransform  ,
invalid_arguments   
)

Definition at line 1735 of file buffer_core_test.cpp.

◆ TEST() [2/17]

TEST ( BufferCore_lookupTransform  ,
compound_xfm_configuration   
)

Definition at line 1159 of file buffer_core_test.cpp.

◆ TEST() [3/17]

TEST ( BufferCore_lookupTransform  ,
helix_configuration   
)

Definition at line 1299 of file buffer_core_test.cpp.

◆ TEST() [4/17]

TEST ( BufferCore_lookupTransform  ,
i_configuration   
)

Definition at line 603 of file buffer_core_test.cpp.

◆ TEST() [5/17]

TEST ( BufferCore_lookupTransform  ,
invalid_arguments   
)

Definition at line 1717 of file buffer_core_test.cpp.

◆ TEST() [6/17]

TEST ( BufferCore_lookupTransform  ,
multi_configuration   
)

Definition at line 1078 of file buffer_core_test.cpp.

◆ TEST() [7/17]

TEST ( BufferCore_lookupTransform  ,
one_link_configuration   
)

Definition at line 941 of file buffer_core_test.cpp.

◆ TEST() [8/17]

TEST ( BufferCore_lookupTransform  ,
ring_45_configuration   
)

Definition at line 1409 of file buffer_core_test.cpp.

◆ TEST() [9/17]

TEST ( BufferCore_lookupTransform  ,
v_configuration   
)

Definition at line 985 of file buffer_core_test.cpp.

◆ TEST() [10/17]

TEST ( BufferCore_lookupTransform  ,
y_configuration   
)

Definition at line 1032 of file buffer_core_test.cpp.

◆ TEST() [11/17]

TEST ( BufferCore_setTransform  ,
NoInsertOnSelfTransform   
)

Definition at line 272 of file buffer_core_test.cpp.

◆ TEST() [12/17]

TEST ( BufferCore_setTransform  ,
NoInsertWithNan   
)

Definition at line 283 of file buffer_core_test.cpp.

◆ TEST() [13/17]

TEST ( BufferCore_setTransform  ,
NoInsertWithNoFrameID   
)

Definition at line 298 of file buffer_core_test.cpp.

◆ TEST() [14/17]

TEST ( BufferCore_setTransform  ,
NoInsertWithNoParentID   
)

Definition at line 312 of file buffer_core_test.cpp.

◆ TEST() [15/17]

TEST ( BufferCore_transformableCallbacks  ,
alreadyTransformable   
)

Definition at line 1769 of file buffer_core_test.cpp.

◆ TEST() [16/17]

TEST ( BufferCore_transformableCallbacks  ,
waitForNewTransform   
)

Definition at line 1785 of file buffer_core_test.cpp.

◆ TEST() [17/17]

TEST ( BufferCore_transformableCallbacks  ,
waitForOldTransform   
)

Definition at line 1812 of file buffer_core_test.cpp.

epsilon
double epsilon
Definition: test_utils.cpp:21
angle
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)


test_tf2
Author(s): Tully Foote, Eitan Marder-Eppstein
autogenerated on Sun May 4 2025 02:16:43