30 #include <gtest/gtest.h> 36 #include "rostest/permuter.h" 40 TEST(StaticTransformPublisher, a_b_different_times)
49 TEST(StaticTransformPublisher, a_c_different_times)
58 TEST(StaticTransformPublisher, a_d_different_times)
62 geometry_msgs::TransformStamped ts;
63 ts.transform.rotation.w = 1;
64 ts.header.frame_id =
"c";
66 ts.child_frame_id =
"d";
83 TEST(StaticTransformPublisher, multiple_parent_test)
88 geometry_msgs::TransformStamped ts;
89 ts.transform.rotation.w = 1;
90 ts.header.frame_id =
"c";
92 ts.child_frame_id =
"d";
102 ts.header.frame_id =
"new_parent";
104 ts.child_frame_id =
"other_child";
106 ts.child_frame_id =
"other_child2";
115 TEST(StaticTransformPublisher, tf_from_param_server_valid)
125 int main(
int argc,
char **argv){
126 testing::InitGoogleTest(&argc, argv);
128 return 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)
TEST(StaticTransformPublisher, a_b_different_times)
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const