PX4 Firmware
PX4 Autopilot Software http://px4.io
rc_loss_alarm.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018 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 rc_loss_alarm.cpp
36  *
37  */
38 
39 #include "rc_loss_alarm.h"
40 
41 #include <px4_platform_common/defines.h>
42 
43 #include <drivers/drv_hrt.h>
44 #include <stdint.h>
45 
46 #include <tunes/tune_definition.h>
47 
49 
50 namespace events
51 {
52 namespace rc_loss
53 {
54 
56  : _subscriber_handler(subscriber_handler)
57 {
58 }
59 
61 {
64  return true;
65  }
66 
67  return false;
68 }
69 
71 {
72  if (!check_for_updates()) {
73  return;
74  }
75 
76  if (!_was_armed &&
77  _vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
78 
79  _was_armed = true; // Once true, impossible to go back to false
80  }
81 
83 
84  _had_rc = true;
85  }
86 
88  _vehicle_status.arming_state != vehicle_status_s::ARMING_STATE_ARMED) {
89  play_tune();
90  _alarm_playing = true;
91 
92  } else if (_alarm_playing) {
93  stop_tune();
94  _alarm_playing = false;
95  }
96 }
97 
99 {
100  struct tune_control_s tune_control = {};
101  tune_control.timestamp = hrt_absolute_time();
102  tune_control.tune_id = static_cast<int>(TuneID::ERROR_TUNE);
103  tune_control.tune_override = 1;
104  tune_control.volume = tune_control_s::VOLUME_LEVEL_MAX;
105 
106  if (_tune_control_pub == nullptr) {
107  _tune_control_pub = orb_advertise_queue(ORB_ID(tune_control), &tune_control, tune_control_s::ORB_QUEUE_LENGTH);
108 
109  } else {
110  orb_publish(ORB_ID(tune_control), _tune_control_pub, &tune_control);
111  }
112 }
113 
115 {
116  struct tune_control_s tune_control = {};
117  tune_control.tune_override = true;
118  tune_control.timestamp = hrt_absolute_time();
119 
120  if (_tune_control_pub == nullptr) {
121  _tune_control_pub = orb_advertise_queue(ORB_ID(tune_control), &tune_control, tune_control_s::ORB_QUEUE_LENGTH);
122 
123  } else {
124  orb_publish(ORB_ID(tune_control), _tune_control_pub, &tune_control);
125  }
126 }
127 
128 } /* namespace rc_loss */
129 } /* namespace events */
RC_Loss_Alarm(const events::SubscriberHandler &subscriber_handler)
void stop_tune()
Publish tune control to interrupt any sound.
int orb_copy(const struct orb_metadata *meta, int handle, void *buffer)
Definition: uORB.cpp:90
Contains a list of uORB subscriptions and maintains their update state.
struct vehicle_status_s _vehicle_status
Definition: rc_loss_alarm.h:74
void play_tune()
Publish tune control to sound alarm.
High-resolution timer with callouts and timekeeping.
uint64_t timestamp
Definition: tune_control.h:57
orb_advert_t orb_advertise_queue(const struct orb_metadata *meta, const void *data, unsigned int queue_size)
Definition: uORB.cpp:48
uint8_t tune_override
Definition: tune_control.h:62
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
Definition: uORB.cpp:70
const events::SubscriberHandler & _subscriber_handler
Definition: rc_loss_alarm.h:79
bool check_for_updates()
check for topic updates
void process()
regularily called to handle state updates
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
uint8_t tune_id
Definition: tune_control.h:61
Tone alarm in the event of RC loss.
uint8_t volume
Definition: tune_control.h:63