30 #include <gtest/gtest.h> 34 #include <rosgraph_msgs/Clock.h> 41 for (uint8_t i = 0; i < 10; ++i)
48 TEST(tf2_ros_transform_listener, time_backwards)
59 rosgraph_msgs::Clock c;
67 geometry_msgs::TransformStamped msg;
69 msg.header.frame_id =
"foo";
70 msg.child_frame_id =
"bar";
71 msg.transform.rotation.x = 1.0;
91 msg.header.frame_id =
"foo2";
92 msg.child_frame_id =
"bar2";
106 int main(
int argc,
char **argv){
107 testing::InitGoogleTest(&argc, argv);
108 ros::init(argc, argv,
"transform_listener_backwards_reset");
109 return RUN_ALL_TESTS();
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Standard implementation of the tf2_ros::BufferInterface abstract data type.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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
Test if a transform is possible.
TEST(tf2_ros_transform_listener, time_backwards)
ROSCPP_DECL void spinOnce()