depth_camera.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
3 #include <ros/ros.h>
4 #include <sensor_msgs/PointCloud2.h>
5 
6 class DepthCameraTest : public testing::Test
7 {
8 protected:
9  virtual void SetUp()
10  {
11  has_new_image_ = false;
12  has_new_depth_ = false;
13  has_new_points_ = false;
14  }
15 
26 public:
27  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
28  {
29  image_stamp_ = msg->header.stamp;
30  has_new_image_ = true;
31  }
32  void depthCallback(const sensor_msgs::ImageConstPtr& msg)
33  {
34  depth_stamp_ = msg->header.stamp;
35  has_new_depth_ = true;
36  }
37  void pointsCallback(const sensor_msgs::PointCloud2ConstPtr& msg)
38  {
39  points_stamp_ = msg->header.stamp;
40  has_new_points_ = true;
41  }
42 };
43 
44 // Test if the camera image is published at all, and that the timestamp
45 // is not too long in the past.
46 TEST_F(DepthCameraTest, cameraSubscribeTest)
47 {
49  cam_sub_ = it.subscribe("camera1/image_raw", 1,
51  dynamic_cast<DepthCameraTest*>(this));
52  depth_sub_ = it.subscribe("camera1/depth/image_raw", 1,
54  dynamic_cast<DepthCameraTest*>(this));
55  points_sub_ = nh_.subscribe("camera1/points", 1,
57  dynamic_cast<DepthCameraTest*>(this));
58 #if 0
59  // wait for gazebo to start publishing
60  // TODO(lucasw) this isn't really necessary since this test
61  // is purely passive
62  bool wait_for_topic = true;
63  while (wait_for_topic)
64  {
65  // @todo this fails without the additional 0.5 second sleep after the
66  // publisher comes online, which means on a slower or more heavily
67  // loaded system it may take longer than 0.5 seconds, and the test
68  // would hang until the timeout is reached and fail.
69  if (cam_sub_.getNumPublishers() > 0)
70  wait_for_topic = false;
71  ros::Duration(0.5).sleep();
72  }
73 #endif
74 
75  while (!has_new_image_ || !has_new_depth_ || !has_new_points_)
76  {
77  ros::spinOnce();
78  ros::Duration(0.1).sleep();
79  }
80 
81  EXPECT_EQ(depth_stamp_.toSec(), image_stamp_.toSec());
82  EXPECT_EQ(depth_stamp_.toSec(), points_stamp_.toSec());
83  // This check depends on the update period (currently 1.0/update_rate = 2.0 seconds)
84  // being much longer than the expected difference between now and the
85  // received image time.
86  const double max_time = 1.0;
87  const ros::Time current_time = ros::Time::now();
88  // TODO(lucasw)
89  // this likely isn't that robust - what if the testing system is really slow?
90  double time_diff;
91  time_diff = (current_time - image_stamp_).toSec();
92  ROS_INFO_STREAM(time_diff);
93  EXPECT_LT(time_diff, max_time);
94 
95  time_diff = (current_time - depth_stamp_).toSec();
96  ROS_INFO_STREAM(time_diff);
97  EXPECT_LT(time_diff, max_time);
98 
99  time_diff = (current_time - points_stamp_).toSec();
100  ROS_INFO_STREAM(time_diff);
101  EXPECT_LT(time_diff, max_time);
102 
103  cam_sub_.shutdown();
104  depth_sub_.shutdown();
105  points_sub_.shutdown();
106 
107  // make sure nothing is subscribing to image_trigger topic
108  // there is no easy API, so call getSystemState
109  XmlRpc::XmlRpcValue args, result, payload;
111  EXPECT_TRUE(ros::master::execute("getSystemState", args, result, payload, true));
112  // [publishers, subscribers, services]
113  // subscribers in index 1 of payload
114  for (int i = 0; i < payload[1].size(); ++i)
115  {
116  // [ [topic1, [topic1Subscriber1...topic1SubscriberN]] ... ]
117  // topic name i is in index 0
118  std::string topic = payload[1][i][0];
119  EXPECT_EQ(topic.find("image_trigger"), std::string::npos);
120  }
121 }
122 
123 int main(int argc, char** argv)
124 {
125  ros::init(argc, argv, "gazebo_depth_camera_test");
126  testing::InitGoogleTest(&argc, argv);
127  return RUN_ALL_TESTS();
128 }
XmlRpc::XmlRpcValue::size
int size() const
msg
msg
DepthCameraTest::imageCallback
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: depth_camera.cpp:27
image_transport::ImageTransport
DepthCameraTest::SetUp
virtual void SetUp()
Definition: depth_camera.cpp:9
DepthCameraTest::cam_sub_
image_transport::Subscriber cam_sub_
Definition: depth_camera.cpp:17
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
main
int main(int argc, char **argv)
Definition: depth_camera.cpp:123
DepthCameraTest::image_stamp_
ros::Time image_stamp_
Definition: depth_camera.cpp:21
ros.h
DepthCameraTest::has_new_depth_
bool has_new_depth_
Definition: depth_camera.cpp:22
ros::spinOnce
ROSCPP_DECL void spinOnce()
DepthCameraTest::nh_
ros::NodeHandle nh_
Definition: depth_camera.cpp:16
image_transport::Subscriber
image_transport::ImageTransport::subscribe
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
DepthCameraTest::has_new_points_
bool has_new_points_
Definition: depth_camera.cpp:24
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
DepthCameraTest
Definition: depth_camera.cpp:6
ros::master::execute
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
TEST_F
TEST_F(DepthCameraTest, cameraSubscribeTest)
Definition: depth_camera.cpp:46
image_transport.h
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
DepthCameraTest::pointsCallback
void pointsCallback(const sensor_msgs::PointCloud2ConstPtr &msg)
Definition: depth_camera.cpp:37
ros::Time
DepthCameraTest::depthCallback
void depthCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: depth_camera.cpp:32
DepthCameraTest::has_new_image_
bool has_new_image_
Definition: depth_camera.cpp:20
DepthCameraTest::points_sub_
ros::Subscriber points_sub_
Definition: depth_camera.cpp:19
ros::Duration::sleep
bool sleep() const
args
DepthCameraTest::depth_stamp_
ros::Time depth_stamp_
Definition: depth_camera.cpp:23
DepthCameraTest::points_stamp_
ros::Time points_stamp_
Definition: depth_camera.cpp:25
DepthCameraTest::depth_sub_
image_transport::Subscriber depth_sub_
Definition: depth_camera.cpp:18
ros::Duration
XmlRpc::XmlRpcValue
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55