PX4 Firmware
PX4 Autopilot Software http://px4.io
uORBFastRpcChannel.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (C) 2015 Mark Charlebois. 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
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 #ifndef _uORBFastRpcChannel_hpp_
34 #define _uORBFastRpcChannel_hpp_
35 
36 #include <stdint.h>
37 #include <string>
38 #include <list>
40 #include <semaphore.h>
41 #include <set>
42 #include <px4_platform_common/sem.h>
43 
44 namespace uORB
45 {
46 class FastRpcChannel;
47 }
48 
50 {
51 public:
52  /**
53  * static method to get the IChannel Implementor.
54  */
56  {
57  return &(_Instance);
58  }
59 
60  /**
61  * @brief Interface to notify the remote entity of a topic being advertised.
62  *
63  * @param messageName
64  * This represents the uORB message name(aka topic); This message name should be
65  * globally unique.
66  * @return
67  * 0 = success; This means the messages is successfully sent to the receiver
68  * Note: This does not mean that the receiver as received it.
69  * otherwise = failure.
70  */
71  virtual int16_t topic_advertised(const char *messageName);
72 
73  /**
74  * @brief Interface to notify the remote entity of a topic being unadvertised
75  * and is no longer publishing messages.
76  *
77  * @param messageName
78  * This represents the uORB message name(aka topic); This message name should be
79  * globally unique.
80  * @return
81  * 0 = success; This means the messages is successfully sent to the receiver
82  * Note: This does not mean that the receiver as received it.
83  * otherwise = failure.
84  */
85  virtual int16_t topic_unadvertised(const char *messageName);
86 
87  /**
88  * @brief Interface to notify the remote entity of interest of a
89  * subscription for a message.
90  *
91  * @param messageName
92  * This represents the uORB message name; This message name should be
93  * globally unique.
94  * @param msgRate
95  * The max rate at which the subscriber can accept the messages.
96  * @return
97  * 0 = success; This means the messages is successfully sent to the receiver
98  * Note: This does not mean that the receiver as received it.
99  * otherwise = failure.
100  */
101  virtual int16_t add_subscription(const char *messageName, int32_t msgRateInHz);
102 
103 
104  /**
105  * @brief Interface to notify the remote entity of removal of a subscription
106  *
107  * @param messageName
108  * This represents the uORB message name; This message name should be
109  * globally unique.
110  * @return
111  * 0 = success; This means the messages is successfully sent to the receiver
112  * Note: This does not necessarily mean that the receiver as received it.
113  * otherwise = failure.
114  */
115  virtual int16_t remove_subscription(const char *messageName);
116 
117  /**
118  * Register Message Handler. This is internal for the IChannel implementer*
119  */
120  virtual int16_t register_handler(uORBCommunicator::IChannelRxHandler *handler);
121 
122 
123  //=========================================================================
124  // INTERFACES FOR Data messages
125  //=========================================================================
126 
127  /**
128  * @brief Sends the data message over the communication link.
129  * @param messageName
130  * This represents the uORB message name; This message name should be
131  * globally unique.
132  * @param length
133  * The length of the data buffer to be sent.
134  * @param data
135  * The actual data to be sent.
136  * @return
137  * 0 = success; This means the messages is successfully sent to the receiver
138  * Note: This does not mean that the receiver as received it.
139  * otherwise = failure.
140  */
141  virtual int16_t send_message(const char *messageName, int32_t length, uint8_t *data);
142 
143  //Function to return the data to krait.
144  int16_t get_data
145  (
146  int32_t *msg_type,
147  char *topic_name,
148  int32_t topic_name_len,
149  uint8_t *data,
150  int32_t data_len_in_bytes,
151  int32_t *bytes_returned
152  );
153 
154  int16_t get_bulk_data(uint8_t *buffer, int32_t max_size_in_bytes, int32_t *returned_bytes, int32_t *topic_count);
155 
156  // function to check if there are subscribers for a topic on adsp.
157  int16_t is_subscriber_present(const char *messageName, int32_t *status);
158 
159  // function to release the blocking semaphore for get_data method.
160  int16_t unblock_get_data_method();
161 
163  {
164  return _RxHandler;
165  }
166 
167  void AddRemoteSubscriber(const std::string &messageName)
168  {
169  _RemoteSubscribers.insert(messageName);
170  }
171  void RemoveRemoteSubscriber(const std::string &messageName)
172  {
173  _RemoteSubscribers.erase(messageName);
174  }
175 
176 private: // data members
179 
180  /// data structure to store the messages to be retrived by Krait.
181  static const int32_t _MAX_MSG_QUEUE_SIZE = 100;
182  static const int32_t _CONTROL_MSG_TYPE_ADD_SUBSCRIBER = 1;
183  static const int32_t _CONTROL_MSG_TYPE_REMOVE_SUBSCRIBER = 2;
184  static const int32_t _DATA_MSG_TYPE = 3;
185  static const int32_t _CONTROL_MSG_TYPE_ADVERTISE = 4;
186  static const int32_t _CONTROL_MSG_TYPE_UNADVERTISE = 5;
187 
189  static const int32_t _PACKET_FIELD_DATA_LEN_IN_BYTES = 2;
190  static const int32_t _PACKET_HEADER_SIZE = 1 + //first byte is the MSG Type
191  _PACKET_FIELD_TOPIC_NAME_LEN_SIZE_IN_BYTES + _PACKET_FIELD_DATA_LEN_IN_BYTES;
192 
193  struct FastRpcDataMsg {
194  int32_t _MaxBufferSize;
195  int32_t _Length;
196  uint8_t *_Buffer;
197  std::string _MsgName;
198  };
199 
201  int32_t _Type;
202  std::string _MsgName;
203  };
204 
206  uint16_t _MsgType;
207  uint16_t _MsgNameLen;
208  uint16_t _DataLen;
209  };
210 
211 
212  struct FastRpcDataMsg _DataMsgQueue[ _MAX_MSG_QUEUE_SIZE ];
213  int32_t _DataQInIndex;
214  int32_t _DataQOutIndex;
215 
216  struct FastRpcControlMsg _ControlMsgQueue[ _MAX_MSG_QUEUE_SIZE ];
219 
220  std::list<std::string> _Subscribers;
221 
222  //utility classes
223  class Mutex
224  {
225  public:
227  {
228  sem_init(&_Sem, 0, 1);
229  }
231  {
232  sem_destroy(&_Sem);
233  }
234  void lock()
235  {
236  sem_wait(&_Sem);
237  }
238  void unlock()
239  {
240  sem_post(&_Sem);
241  }
242  private:
243  sem_t _Sem;
244 
245  Mutex(const Mutex &);
246 
247  Mutex &operator=(const Mutex &);
248  };
249 
250  class Semaphore
251  {
252  public:
254  {
255  sem_init(&_Sem, 0, 0);
256  /* _Sem use case is a signal */
257  px4_sem_setprotocol(&_Sem, SEM_PRIO_NONE);
258  }
260  {
261  sem_destroy(&_Sem);
262  }
263  void post()
264  {
265  sem_post(&_Sem);
266  }
267  void wait()
268  {
269  sem_wait(&_Sem);
270  }
271  private:
272  sem_t _Sem;
273  Semaphore(const Semaphore &);
274  Semaphore &operator=(const Semaphore &);
275 
276  };
277 
280 
281 private://class members.
282  /// constructor.
283  FastRpcChannel();
284 
285  void check_and_expand_data_buffer(int32_t index, int32_t length);
286 
287  bool IsControlQFull();
288  bool IsControlQEmpty();
289  bool IsDataQFull();
290  bool IsDataQEmpty();
291  int32_t DataQSize();
292  int32_t ControlQSize();
293 
294  int32_t get_msg_size_at(bool isData, int32_t index);
295  int32_t copy_msg_to_buffer(bool isData, int32_t src_index, uint8_t *dst_buffer, int32_t offset, int32_t dst_buffer_len);
296  int16_t control_msg_queue_add(int32_t msgtype, const char *messageName);
297 
298  std::set<std::string> _RemoteSubscribers;
299 };
300 
301 #endif /* _uORBFastRpcChannel_hpp_ */
uORBCommunicator::IChannelRxHandler * GetRxHandler()
static const int32_t _MAX_MSG_QUEUE_SIZE
data structure to store the messages to be retrived by Krait.
static struct vehicle_status_s status
Definition: Commander.cpp:138
static const int32_t _PACKET_FIELD_TOPIC_NAME_LEN_SIZE_IN_BYTES
virtual int16_t add_subscription(const char *messageName, int32_t msgRateInHz)
Interface to notify the remote entity of interest of a subscription for a message.
FastRpcChannel()
constructor.
void AddRemoteSubscriber(const std::string &messageName)
static uORB::FastRpcChannel * GetInstance()
static method to get the IChannel Implementor.
struct FastRpcControlMsg _ControlMsgQueue[_MAX_MSG_QUEUE_SIZE]
virtual int16_t send_message(const char *messageName, int32_t length, uint8_t *data)
Sends the data message over the communication link.
void check_and_expand_data_buffer(int32_t index, int32_t length)
void RemoveRemoteSubscriber(const std::string &messageName)
struct FastRpcDataMsg _DataMsgQueue[_MAX_MSG_QUEUE_SIZE]
int16_t control_msg_queue_add(int32_t msgtype, const char *messageName)
uint8_t * data
Definition: dataman.cpp:149
static const int32_t _CONTROL_MSG_TYPE_ADD_SUBSCRIBER
virtual int16_t topic_unadvertised(const char *messageName)
Interface to notify the remote entity of a topic being unadvertised and is no longer publishing messa...
uORBCommunicator::IChannelRxHandler * _RxHandler
int32_t copy_msg_to_buffer(bool isData, int32_t src_index, uint8_t *dst_buffer, int32_t offset, int32_t dst_buffer_len)
int16_t is_subscriber_present(const char *messageName, int32_t *status)
static const int32_t _DATA_MSG_TYPE
static const int32_t _CONTROL_MSG_TYPE_ADVERTISE
int16_t get_bulk_data(uint8_t *buffer, int32_t max_size_in_bytes, int32_t *returned_bytes, int32_t *topic_count)
Class passed to the communication link implement to provide callback for received messages over a cha...
static const int32_t _CONTROL_MSG_TYPE_UNADVERTISE
virtual int16_t remove_subscription(const char *messageName)
Interface to notify the remote entity of removal of a subscription.
std::list< std::string > _Subscribers
static uORB::FastRpcChannel _Instance
std::set< std::string > _RemoteSubscribers
virtual int16_t topic_advertised(const char *messageName)
Interface to notify the remote entity of a topic being advertised.
Interface to enable remote subscriptions.
static const int32_t _PACKET_HEADER_SIZE
int32_t get_msg_size_at(bool isData, int32_t index)
static const int32_t _PACKET_FIELD_DATA_LEN_IN_BYTES
virtual int16_t register_handler(uORBCommunicator::IChannelRxHandler *handler)
Register Message Handler.
int16_t get_data(int32_t *msg_type, char *topic_name, int32_t topic_name_len, uint8_t *data, int32_t data_len_in_bytes, int32_t *bytes_returned)
static const int32_t _CONTROL_MSG_TYPE_REMOVE_SUBSCRIBER