Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <gtest/gtest.h>
00031 #include <tf2/buffer_core.h>
00032 #include <sys/time.h>
00033 #include <ros/ros.h>
00034 #include "tf2/LinearMath/Vector3.h"
00035 #include "tf2/exceptions.h"
00036
00037 TEST(tf2, setTransformFail)
00038 {
00039 tf2::BufferCore tfc;
00040 geometry_msgs::TransformStamped st;
00041 EXPECT_FALSE(tfc.setTransform(st, "authority1"));
00042
00043 }
00044
00045 TEST(tf2, setTransformValid)
00046 {
00047 tf2::BufferCore tfc;
00048 geometry_msgs::TransformStamped st;
00049 st.header.frame_id = "foo";
00050 st.header.stamp = ros::Time(1.0);
00051 st.child_frame_id = "child";
00052 st.transform.rotation.w = 1;
00053 EXPECT_TRUE(tfc.setTransform(st, "authority1"));
00054
00055 }
00056
00057 TEST(tf2, setTransformInvalidQuaternion)
00058 {
00059 tf2::BufferCore tfc;
00060 geometry_msgs::TransformStamped st;
00061 st.header.frame_id = "foo";
00062 st.header.stamp = ros::Time(1.0);
00063 st.child_frame_id = "child";
00064 st.transform.rotation.w = 0;
00065 EXPECT_FALSE(tfc.setTransform(st, "authority1"));
00066
00067 }
00068
00069 TEST(tf2_lookupTransform, LookupException_Nothing_Exists)
00070 {
00071 tf2::BufferCore tfc;
00072 EXPECT_THROW(tfc.lookupTransform("a", "b", ros::Time().fromSec(1.0)), tf2::LookupException);
00073
00074 }
00075
00076 TEST(tf2_canTransform, Nothing_Exists)
00077 {
00078 tf2::BufferCore tfc;
00079 EXPECT_FALSE(tfc.canTransform("a", "b", ros::Time().fromSec(1.0)));
00080
00081 std::string error_msg = std::string();
00082 EXPECT_FALSE(tfc.canTransform("a", "b", ros::Time().fromSec(1.0), &error_msg));
00083 ASSERT_STREQ(error_msg.c_str(), "canTransform: target_frame a does not exist. canTransform: source_frame b does not exist.");
00084
00085 }
00086
00087 TEST(tf2_lookupTransform, LookupException_One_Exists)
00088 {
00089 tf2::BufferCore tfc;
00090 geometry_msgs::TransformStamped st;
00091 st.header.frame_id = "foo";
00092 st.header.stamp = ros::Time(1.0);
00093 st.child_frame_id = "child";
00094 st.transform.rotation.w = 1;
00095 EXPECT_TRUE(tfc.setTransform(st, "authority1"));
00096 EXPECT_THROW(tfc.lookupTransform("foo", "bar", ros::Time().fromSec(1.0)), tf2::LookupException);
00097
00098 }
00099
00100 TEST(tf2_canTransform, One_Exists)
00101 {
00102 tf2::BufferCore tfc;
00103 geometry_msgs::TransformStamped st;
00104 st.header.frame_id = "foo";
00105 st.header.stamp = ros::Time(1.0);
00106 st.child_frame_id = "child";
00107 st.transform.rotation.w = 1;
00108 EXPECT_TRUE(tfc.setTransform(st, "authority1"));
00109 EXPECT_FALSE(tfc.canTransform("foo", "bar", ros::Time().fromSec(1.0)));
00110 }
00111
00112
00113 int main(int argc, char **argv){
00114 testing::InitGoogleTest(&argc, argv);
00115 ros::Time::init();
00116 return RUN_ALL_TESTS();
00117 }