rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
rosout_test_helper.h
Go to the documentation of this file.
1 #ifndef _RAPID_TESTING_ROSOUT_TEST_HELPER_H_
2 #define _RAPID_TESTING_ROSOUT_TEST_HELPER_H_
3 
4 #include <vector>
5 
6 #include "ros/ros.h"
7 #include "rosgraph_msgs/Log.h"
8 
9 namespace rapid {
10 // Helps check that messages were logged in unit tests.
11 //
12 // Usage:
13 // RosoutTestHelper rosout;
14 // rosout.Start();
15 // Foo(); // This will publish an error message.
16 // rosout.WaitForMessageCount(1, ros::Duration(1.0));
17 // EXPECT_TRUE(rosout.WasErrorPublished());
19  public:
21 
22  // Start subscribing to /rosout.
23  void Start();
24 
25  // Waits until a certain number of messages have been received.
26  // Returns true if the number of received messages within the timeout is at
27  // least num_messages, false otherwise.
28  bool WaitForMessageCount(size_t num_messages,
29  const ros::Duration& timeout) const;
30 
31  // Clear message list.
32  void Clear();
33 
34  // Get the messages that were published since calling Start();
35  std::vector<rosgraph_msgs::Log> messages() const;
36 
37  // Returns true if at least one debug-level message was published.
38  bool WasDebugPublished() const;
39 
40  // Returns true if at least one info-level message was published.
41  bool WasInfoPublished() const;
42 
43  // Returns true if at least one warning-level message was published.
44  bool WasWarningPublished() const;
45 
46  // Returns true if at least one error-level message was published.
47  bool WasErrorPublished() const;
48 
49  // Returns true if at least one fatal-level message was published.
50  bool WasFatalPublished() const;
51 
52  private:
53  void Callback(const rosgraph_msgs::Log& msg);
54  bool WasLevelPublished(int8_t level) const;
55 
56  ros::NodeHandle nh_;
57  ros::Subscriber rosout_sub_;
58  std::vector<rosgraph_msgs::Log> messages_;
59 };
60 } // namespace rapid
61 
62 #endif // _RAPID_TESTING_ROSOUT_TEST_HELPER_H_
std::vector< rosgraph_msgs::Log > messages() const
bool WasInfoPublished() const
bool WaitForMessageCount(size_t num_messages, const ros::Duration &timeout) const
bool WasDebugPublished() const
bool WasFatalPublished() const
bool WasWarningPublished() const
bool WasErrorPublished() const