33 #include <geometry_msgs/TransformStamped.h> 35 #include <sensor_msgs/PointCloud2.h> 41 #include <gtest/gtest.h> 45 void GenerateSinglePointPointcloud2(
46 sensor_msgs::PointCloud2& cloud,
47 const float x,
const float y,
const float z)
51 cloud.is_bigendian =
false;
52 cloud.is_dense =
false;
54 modifier.setPointCloud2FieldsByString(1,
"xyz");
63 void publishSinglePointPointcloud2(
65 const float x,
const float y,
const float z,
66 const std::string frame_id,
69 sensor_msgs::PointCloud2 cloud;
70 cloud.header.frame_id = frame_id;
71 cloud.header.stamp = stamp;
72 GenerateSinglePointPointcloud2(cloud, x, y, z);
77 TEST(TransformFailure, NoDeadAgainstTransformFailure)
85 publishSinglePointPointcloud2(
97 for (
auto node : nodes)
99 if (node ==
"/mcl_3dl")
108 std::cerr <<
"mcl_3dl started" << std::endl;
115 geometry_msgs::TransformStamped trans;
119 trans.header.frame_id =
"laser_link_base";
120 trans.child_frame_id =
"laser_link";
123 trans.header.frame_id =
"map";
124 trans.child_frame_id =
"odom";
129 trans.header.frame_id =
"base_link";
130 trans.child_frame_id =
"laser_link_base";
135 trans.header.frame_id =
"odom";
136 trans.child_frame_id =
"base_link";
142 publishSinglePointPointcloud2(
152 int main(
int argc,
char** argv)
154 testing::InitGoogleTest(&argc, argv);
155 ros::init(argc, argv,
"test_transform_failure");
157 return RUN_ALL_TESTS();
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)
std::vector< std::string > V_string
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL bool getNodes(V_string &nodes)
ROSCPP_DECL void spinOnce()