rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
publisher.h
Go to the documentation of this file.
1 #ifndef _RAPID_ROS_PUBLISHER_H_
2 #define _RAPID_ROS_PUBLISHER_H_
3 
4 #include <vector>
5 
6 #include "ros/ros.h"
7 
8 namespace rapid_ros {
9 // DECLARATIONS ----------------------------------------------------------------
10 // Interface wrapper for ros::Publisher
11 template <class Message>
13  public:
14  virtual ~PublisherInterface() {}
15  virtual void publish(const Message& message) const = 0;
16  virtual bool IsValid() const = 0;
17 };
18 
19 // A wrapper around a real ROS publisher.
20 template <class Message>
21 class Publisher : public PublisherInterface<Message> {
22  public:
23  explicit Publisher(const ros::Publisher& pub);
24  void publish(const Message& message) const;
25  bool IsValid() const;
26 
27  private:
28  ros::Publisher pub_;
29 };
30 
31 template <class Message>
33  std::vector<Message> messages;
34 };
35 
36 // A mock publisher.
37 template <class Message>
38 class MockPublisher : public PublisherInterface<Message> {
39  public:
40  MockPublisher();
41  void publish(const Message& message) const;
42  bool IsValid() const;
43 
44  // Mock helpers
45  Message last_message() const;
46  std::vector<Message> sent_messages() const;
47  void set_valid(bool valid);
48 
49  private:
51  bool is_valid_;
52 };
53 
54 // DEFINITIONS -----------------------------------------------------------------
55 template <class Message>
56 Publisher<Message>::Publisher(const ros::Publisher& pub)
57  : pub_(pub) {}
58 
59 template <class Message>
60 void Publisher<Message>::publish(const Message& message) const {
61  pub_.publish(message);
62 }
63 
64 template <class Message>
66  if (pub_) {
67  return true;
68  } else {
69  return false;
70  }
71 }
72 
73 template <class Message>
75  : sent_(new MessageHistory<Message>), is_valid_(true) {}
76 
77 template <class Message>
78 void MockPublisher<Message>::publish(const Message& message) const {
79  if (is_valid_) {
80  sent_->messages.push_back(message);
81  }
82 }
83 
84 template <class Message>
86  return is_valid_;
87 }
88 
89 template <class Message>
91  return sent_->messages.back();
92 }
93 
94 template <class Message>
95 std::vector<Message> MockPublisher<Message>::sent_messages() const {
96  return sent_->messages;
97 }
98 
99 template <class Message>
101  is_valid_ = valid;
102 }
103 } // namespace rapid_ros
104 
105 #endif // _RAPID_ROS_PUBLISHER_H_
virtual bool IsValid() const =0
bool IsValid() const
Definition: publisher.h:65
Message last_message() const
Definition: publisher.h:90
void set_valid(bool valid)
Definition: publisher.h:100
std::vector< Message > messages
Definition: publisher.h:33
void publish(const Message &message) const
Definition: publisher.h:78
void publish(const Message &message) const
Definition: publisher.h:60
virtual void publish(const Message &message) const =0
Publisher(const ros::Publisher &pub)
Definition: publisher.h:56
bool IsValid() const
Definition: publisher.h:85
std::vector< Message > sent_messages() const
Definition: publisher.h:95