35 #include <gtest/gtest.h> 39 #include <sensor_msgs/Image.h> 40 #include <sensor_msgs/CameraInfo.h> 41 #include <sensor_msgs/LaserScan.h> 50 void callback(
const sensor_msgs::LaserScanConstPtr& msg){
54 TEST(transform_listener, commsTest)
68 uint16_t value = 0x0F;
71 info_msg_.reset(
new sensor_msgs::CameraInfo);
75 info_msg_->distortion_model =
"plumb_bob";
101 size_t number_published = 10;
102 double sleep_duration = 1.0/30.0;
105 for(
size_t i = 0; i < number_published; i++){
120 int main(
int argc,
char **argv){
121 testing::InitGoogleTest(&argc, argv);
122 ros::init(argc, argv,
"depthimage_to_laserscan_unittest");
126 return RUN_ALL_TESTS();
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())
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()