36 #include <gtest/gtest.h> 40 static const double EPS = 1e-3;
48 EXPECT_NEAR(v_simple.getOrigin().getX(), -9,
EPS);
49 EXPECT_NEAR(v_simple.getOrigin().getY(), 18,
EPS);
50 EXPECT_NEAR(v_simple.getOrigin().getZ(), 27,
EPS);
55 EXPECT_NEAR(v_advanced.getOrigin().getX(), -9,
EPS);
56 EXPECT_NEAR(v_advanced.getOrigin().getY(), 18,
EPS);
57 EXPECT_NEAR(v_advanced.getOrigin().getZ(), 27,
EPS);
68 EXPECT_NEAR(v_simple.getX(), -9,
EPS);
69 EXPECT_NEAR(v_simple.getY(), 18,
EPS);
70 EXPECT_NEAR(v_simple.getZ(), 27,
EPS);
75 EXPECT_NEAR(v_advanced.getX(), -9,
EPS);
76 EXPECT_NEAR(v_advanced.getY(), 18,
EPS);
77 EXPECT_NEAR(v_advanced.getZ(), 27,
EPS);
83 int main(
int argc,
char **argv){
84 testing::InitGoogleTest(&argc, argv);
91 geometry_msgs::TransformStamped
t;
92 t.transform.translation.x = 10;
93 t.transform.translation.y = 20;
94 t.transform.translation.z = 30;
95 t.transform.rotation.x = 1;
97 t.header.frame_id =
"A";
98 t.child_frame_id =
"B";
101 int ret = RUN_ALL_TESTS();
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
geometry_msgs::TransformStamped t
tf2_ros::Buffer * tf_buffer
T & transform(const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
TEST(TfBullet, Transform)