PX4 Firmware
PX4 Autopilot Software http://px4.io
uORBDeviceMaster.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2016 PX4 Development Team. 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 
34 #pragma once
35 
36 #include <stdint.h>
37 
38 #include "uORBCommon.hpp"
39 #include <px4_platform_common/posix.h>
40 
41 namespace uORB
42 {
43 class DeviceNode;
44 class DeviceMaster;
45 class Manager;
46 }
47 
48 #include <string.h>
49 #include <stdlib.h>
50 
51 #include <containers/List.hpp>
52 
53 /**
54  * Master control device for ObjDev.
55  *
56  * Used primarily to create new objects via the ORBIOCCREATE
57  * ioctl.
58  */
60 {
61 public:
62 
63  int advertise(const struct orb_metadata *meta, bool is_advertiser, int *instance, int priority);
64 
65  /**
66  * Public interface for getDeviceNodeLocked(). Takes care of synchronization.
67  * @return node if exists, nullptr otherwise
68  */
69  uORB::DeviceNode *getDeviceNode(const char *node_name);
70  uORB::DeviceNode *getDeviceNode(const struct orb_metadata *meta, const uint8_t instance);
71 
72  /**
73  * Print statistics for each existing topic.
74  * @param reset if true, reset statistics afterwards
75  */
76  void printStatistics(bool reset);
77 
78  /**
79  * Continuously print statistics, like the unix top command for processes.
80  * Exited when the user presses the enter key.
81  * @param topic_filter list of topic filters: if set, each string can be a substring for topics to match.
82  * Or it can be '-a', which means to print all topics instead of only currently publishing ones.
83  * @param num_filters
84  */
85  void showTop(char **topic_filter, int num_filters);
86 
87 private:
88  // Private constructor, uORB::Manager takes care of its creation
89  DeviceMaster();
90  ~DeviceMaster();
91 
95  unsigned int last_pub_msg_count;
96  uint32_t lost_msg_delta;
97  unsigned int pub_msg_delta;
99  };
100 
101  int addNewDeviceNodes(DeviceNodeStatisticsData **first_node, int &num_topics, size_t &max_topic_name_length,
102  char **topic_filter, int num_filters);
103 
104  friend class uORB::Manager;
105 
106  /**
107  * Find a node give its name.
108  * _lock must already be held when calling this.
109  * @return node if exists, nullptr otherwise
110  */
111  uORB::DeviceNode *getDeviceNodeLocked(const struct orb_metadata *meta, const uint8_t instance);
112 
114 
116 
117  px4_sem_t _lock; /**< lock to protect access to all class members (also for derived classes) */
118 
119  void lock() { do {} while (px4_sem_wait(&_lock) != 0); }
120  void unlock() { px4_sem_post(&_lock); }
121 };
List< uORB::DeviceNode * > _node_list
An intrusive linked list.
int addNewDeviceNodes(DeviceNodeStatisticsData **first_node, int &num_topics, size_t &max_topic_name_length, char **topic_filter, int num_filters)
int reset(enum LPS22HB_BUS busid)
Reset the driver.
LidarLite * instance
Definition: ll40ls.cpp:65
uORB::DeviceNode * getDeviceNodeLocked(const struct orb_metadata *meta, const uint8_t instance)
Find a node give its name.
Definition: List.hpp:59
Per-object device instance.
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
hrt_abstime _last_statistics_output
void showTop(char **topic_filter, int num_filters)
Continuously print statistics, like the unix top command for processes.
Object metadata.
Definition: uORB.h:50
px4_sem_t _lock
lock to protect access to all class members (also for derived classes)
Master control device for ObjDev.
uORB::DeviceNode * getDeviceNode(const char *node_name)
Public interface for getDeviceNodeLocked().
void printStatistics(bool reset)
Print statistics for each existing topic.
int advertise(const struct orb_metadata *meta, bool is_advertiser, int *instance, int priority)
This is implemented as a singleton.
Definition: uORBManager.hpp:64