test_tf2_sensor_msgs.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 
32 #include <geometry_msgs/PoseStamped.h>
34 #include <ros/ros.h>
35 #include <gtest/gtest.h>
36 #include <tf2_ros/buffer.h>
37 
39 static const double EPS = 1e-3;
40 
41 
42 TEST(Tf2Sensor, PointCloud2)
43 {
44  sensor_msgs::PointCloud2 cloud;
45  sensor_msgs::PointCloud2Modifier modifier(cloud);
46  modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
47  modifier.resize(1);
48 
49  sensor_msgs::PointCloud2Iterator<float> iter_x(cloud, "x");
50  sensor_msgs::PointCloud2Iterator<float> iter_y(cloud, "y");
51  sensor_msgs::PointCloud2Iterator<float> iter_z(cloud, "z");
52 
53  *iter_x = 1;
54  *iter_y = 2;
55  *iter_z = 3;
56 
57  cloud.header.stamp = ros::Time(2);
58  cloud.header.frame_id = "A";
59 
60  // simple api
61  sensor_msgs::PointCloud2 cloud_simple = tf_buffer->transform(cloud, "B", ros::Duration(2.0));
62  sensor_msgs::PointCloud2Iterator<float> iter_x_after(cloud_simple, "x");
63  sensor_msgs::PointCloud2Iterator<float> iter_y_after(cloud_simple, "y");
64  sensor_msgs::PointCloud2Iterator<float> iter_z_after(cloud_simple, "z");
65  EXPECT_NEAR(*iter_x_after, -9, EPS);
66  EXPECT_NEAR(*iter_y_after, 18, EPS);
67  EXPECT_NEAR(*iter_z_after, 27, EPS);
68 
69  // advanced api
70  sensor_msgs::PointCloud2 cloud_advanced = tf_buffer->transform(cloud, "B", ros::Time(2.0),
71  "A", ros::Duration(3.0));
72  sensor_msgs::PointCloud2Iterator<float> iter_x_advanced(cloud_advanced, "x");
73  sensor_msgs::PointCloud2Iterator<float> iter_y_advanced(cloud_advanced, "y");
74  sensor_msgs::PointCloud2Iterator<float> iter_z_advanced(cloud_advanced, "z");
75  EXPECT_NEAR(*iter_x_advanced, -9, EPS);
76  EXPECT_NEAR(*iter_y_advanced, 18, EPS);
77  EXPECT_NEAR(*iter_z_advanced, 27, EPS);
78 }
79 
80 int main(int argc, char **argv){
81  testing::InitGoogleTest(&argc, argv);
82  ros::init(argc, argv, "test");
84 
85  tf_buffer = new tf2_ros::Buffer();
86 
87  // populate buffer
88  geometry_msgs::TransformStamped t;
89  t.transform.translation.x = 10;
90  t.transform.translation.y = 20;
91  t.transform.translation.z = 30;
92  t.transform.rotation.x = 1;
93  t.transform.rotation.y = 0;
94  t.transform.rotation.z = 0;
95  t.transform.rotation.w = 0;
96  t.header.stamp = ros::Time(2.0);
97  t.header.frame_id = "A";
98  t.child_frame_id = "B";
99  tf_buffer->setTransform(t, "test");
100 
101  int ret = RUN_ALL_TESTS();
102  delete tf_buffer;
103  return ret;
104 }
TEST(Tf2Sensor, PointCloud2)
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
static const double EPS
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
T & transform(const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
int main(int argc, char **argv)
void setPointCloud2FieldsByString(int n_fields,...)
tf2_ros::Buffer * tf_buffer


tf2_sensor_msgs
Author(s): Vincent Rabaud
autogenerated on Fri Oct 16 2020 19:09:07