depthimage_to_laserscan_rostest.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, 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 /*
31  * Author: Chad Rockey
32  */
33 
34 // Bring in gtest
35 #include <gtest/gtest.h>
36 
37 #include <ros/ros.h>
38 
39 #include <sensor_msgs/Image.h>
40 #include <sensor_msgs/CameraInfo.h>
41 #include <sensor_msgs/LaserScan.h>
43 
44 // Outputs
45 sensor_msgs::ImagePtr depth_msg_;
46 sensor_msgs::CameraInfoPtr info_msg_;
47 
49 
50 void callback(const sensor_msgs::LaserScanConstPtr& msg){
52 }
53 
54 TEST(transform_listener, commsTest)
55 {
57 
58  // Set up output messages
59  depth_msg_.reset(new sensor_msgs::Image);
60  depth_msg_->header.seq = 42;
61  depth_msg_->header.stamp.fromNSec(1234567890);
62  depth_msg_->header.frame_id = "frame";
63  depth_msg_->height = 480;
64  depth_msg_->width = 640;
66  depth_msg_->is_bigendian = false;
67  depth_msg_->step = depth_msg_->width*2; // 2 bytes per pixel
68  uint16_t value = 0x0F;
69  depth_msg_->data.assign(depth_msg_->height*depth_msg_->step, value); // Sets all values to 3.855m
70 
71  info_msg_.reset(new sensor_msgs::CameraInfo);
72  info_msg_->header = depth_msg_->header;
73  info_msg_->height = depth_msg_->height;
74  info_msg_->width = depth_msg_->width;
75  info_msg_->distortion_model = "plumb_bob";
76  info_msg_->D.resize(5); // All 0, no distortion
77  info_msg_->K[0] = 570.3422241210938;
78  info_msg_->K[2] = 314.5;
79  info_msg_->K[4] = 570.3422241210938;
80  info_msg_->K[5] = 235.5;
81  info_msg_->K[8] = 1.0;
82  info_msg_->R[0] = 1.0;
83  info_msg_->R[4] = 1.0;
84  info_msg_->R[8] = 1.0;
85  info_msg_->P[0] = 570.3422241210938;
86  info_msg_->P[2] = 314.5;
87  info_msg_->P[5] = 570.3422241210938;
88  info_msg_->P[6] = 235.5;
89  info_msg_->P[10] = 1.0;
90 
91  // Set up publisher
92  ros::Publisher pub = n.advertise<sensor_msgs::Image>("image", 5);
93  ros::Publisher pub_info = n.advertise<sensor_msgs::CameraInfo>("camera_info", 5);
94 
95  // Subscribe to output
96  ros::Subscriber sub = n.subscribe("scan", 20, callback);
97 
98  // Sleep to allow connections to settle
99  ros::Duration(5.0).sleep();
100 
101  size_t number_published = 10;
102  double sleep_duration = 1.0/30.0;
103 
104  // Publish some data
105  for(size_t i = 0; i < number_published; i++){
106  pub.publish(depth_msg_);
107  pub_info.publish(info_msg_);
108  ros::Duration(sleep_duration).sleep();
109  ros::spinOnce();
110  }
111 
112  // Wait a while longer
113  ros::Duration(2.0).sleep();
114  ros::spinOnce();
115 
116  EXPECT_EQ(number_published, message_count_);
117 }
118 
119 
120 int main(int argc, char **argv){
121  testing::InitGoogleTest(&argc, argv);
122  ros::init(argc, argv, "depthimage_to_laserscan_unittest");
123 
124  message_count_ = 0;
125 
126  return RUN_ALL_TESTS();
127 }
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool sleep() const
void callback(const sensor_msgs::LaserScanConstPtr &msg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
sensor_msgs::CameraInfoPtr info_msg_
const std::string TYPE_16UC1
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sensor_msgs::ImagePtr depth_msg_
TEST(transform_listener, commsTest)
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()


depthimage_to_laserscan
Author(s): Chad Rockey
autogenerated on Sun Jan 5 2020 03:45:46