PX4 Firmware
PX4 Autopilot Software http://px4.io
SubscriptionInterval.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2019 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 /**
35  * @file SubscriptionInterval.hpp
36  *
37  */
38 
39 #pragma once
40 
41 #include <uORB/uORB.h>
42 #include <px4_platform_common/defines.h>
43 
44 #include "uORBDeviceNode.hpp"
45 #include "uORBManager.hpp"
46 #include "uORBUtils.hpp"
47 
48 #include "Subscription.hpp"
49 
50 namespace uORB
51 {
52 
53 // Base subscription wrapper class
55 {
56 public:
57 
58  /**
59  * Constructor
60  *
61  * @param meta The uORB metadata (usually from the ORB_ID() macro) for the topic.
62  * @param interval The requested maximum update interval in microseconds.
63  * @param instance The instance for multi sub.
64  */
65  SubscriptionInterval(const orb_metadata *meta, uint32_t interval_us = 0, uint8_t instance = 0) :
66  _subscription{meta, instance},
67  _interval_us(interval_us)
68  {}
69 
71 
72  ~SubscriptionInterval() = default;
73 
74  bool subscribe() { return _subscription.subscribe(); }
75 
76  bool advertised() { return _subscription.advertised(); }
77 
78  /**
79  * Check if there is a new update.
80  * */
81  bool updated()
82  {
84  return _subscription.updated();
85  }
86 
87  return false;
88  }
89 
90  /**
91  * Copy the struct if updated.
92  * @param dst The destination pointer where the struct will be copied.
93  * @return true only if topic was updated and copied successfully.
94  */
95  bool update(void *dst)
96  {
97  if (updated()) {
98  return copy(dst);
99  }
100 
101  return false;
102  }
103 
104  /**
105  * Copy the struct
106  * @param dst The destination pointer where the struct will be copied.
107  * @return true only if topic was copied successfully.
108  */
109  bool copy(void *dst)
110  {
111  if (_subscription.copy(dst)) {
113  return true;
114  }
115 
116  return false;
117  }
118 
119  bool valid() const { return _subscription.valid(); }
120 
121  uint8_t get_instance() const { return _subscription.get_instance(); }
123 
124  /**
125  * Set the interval in microseconds
126  * @param interval The interval in microseconds.
127  */
128  void set_interval_us(uint32_t interval) { _interval_us = interval; }
129 
130  /**
131  * Set the interval in milliseconds
132  * @param interval The interval in milliseconds.
133  */
134  void set_interval_ms(uint32_t interval) { _interval_us = interval * 1000; }
135 
136 protected:
137 
139  uint64_t _last_update{0}; // last update in microseconds
140  uint32_t _interval_us{0}; // maximum update interval in microseconds
141 
142 };
143 
144 } // namespace uORB
bool copy(void *dst)
Copy the struct.
bool update(void *dst)
Copy the struct if updated.
API for the uORB lightweight object broker.
bool updated()
Check if there is a new update.
uint8_t get_instance() const
void set_interval_us(uint32_t interval)
Set the interval in microseconds.
LidarLite * instance
Definition: ll40ls.cpp:65
void set_interval_ms(uint32_t interval)
Set the interval in milliseconds.
SubscriptionInterval(const orb_metadata *meta, uint32_t interval_us=0, uint8_t instance=0)
Constructor.
bool valid() const
static hrt_abstime hrt_elapsed_time(const hrt_abstime *then)
Compute the delta between a timestamp taken in the past and now.
Definition: drv_hrt.h:102
bool updated()
Check if there is a new update.
Object metadata.
Definition: uORB.h:50
orb_id_t get_topic() const
bool copy(void *dst)
Copy the struct.
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).