Firmware
uavcan_servers.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2014 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 <px4_config.h>
37 #include "uavcan_driver.hpp"
38 #include <drivers/device/device.h>
39 #include <perf/perf_counter.h>
40 
41 #include <uavcan/node/sub_node.hpp>
42 #include <uavcan/protocol/node_status_monitor.hpp>
43 #include <uavcan/protocol/param/GetSet.hpp>
44 #include <uavcan/protocol/param/ExecuteOpcode.hpp>
45 
46 #include <uavcan/protocol/dynamic_node_id_server/centralized.hpp>
47 #include <uavcan/protocol/node_info_retriever.hpp>
48 #include <uavcan_posix/basic_file_server_backend.hpp>
49 #include <uavcan/protocol/firmware_update_trigger.hpp>
50 #include <uavcan/protocol/file_server.hpp>
51 #include <uavcan_posix/dynamic_node_id_server/file_event_tracer.hpp>
52 #include <uavcan_posix/dynamic_node_id_server/file_storage_backend.hpp>
53 #include <uavcan_posix/firmware_version_checker.hpp>
54 #include <uavcan/equipment/esc/RawCommand.hpp>
55 #include <uavcan/equipment/indication/BeepCommand.hpp>
56 #include <uavcan/protocol/enumeration/Begin.hpp>
57 #include <uavcan/protocol/enumeration/Indication.hpp>
58 
59 #include "uavcan_module.hpp"
60 #include "uavcan_virtual_can_driver.hpp"
61 
75 {
76  static constexpr unsigned NumIfaces = 1; // UAVCAN_STM32_NUM_IFACES
77 
78  static constexpr unsigned StackSize = 6000;
79  static constexpr unsigned Priority = 120;
80 
81  static constexpr unsigned VirtualIfaceBlockAllocationQuota = 80;
82 
83  static constexpr float BeepFrequencyGenericIndication = 1000.0F;
84  static constexpr float BeepFrequencySuccess = 2000.0F;
85  static constexpr float BeepFrequencyError = 100.0F;
86 
87 public:
88  UavcanServers(uavcan::INode &main_node);
89 
90  virtual ~UavcanServers();
91 
92  static int start(uavcan::INode &main_node);
93  static int stop();
94 
95  uavcan::SubNode<> &get_node() { return _subnode; }
96 
97  static UavcanServers *instance() { return _instance; }
98 
99  /*
100  * Set the main node's pointer to to the injector
101  * This is a work around as main_node.getDispatcher().remeveRxFrameListener();
102  * would require a dynamic cast and rtti is not enabled.
103  */
104  void attachITxQueueInjector(ITxQueueInjector **injector) {*injector = &_vdriver;}
105 
106  void requestCheckAllNodesFirmwareAndUpdate() { _check_fw = true; }
107 
108  bool guessIfAllDynamicNodesAreAllocated() { return _server_instance.guessIfAllDynamicNodesAreAllocated(); }
109 
110 private:
111  pthread_t _subnode_thread;
112  pthread_mutex_t _subnode_mutex;
113  volatile bool _subnode_thread_should_exit = false;
114 
115  int init();
116 
117  pthread_addr_t run(pthread_addr_t);
118 
119  static UavcanServers *_instance;
120 
121  VirtualCanDriver _vdriver;
122 
123  uavcan::SubNode<> _subnode;
124  uavcan::INode &_main_node;
125 
126  uavcan_posix::dynamic_node_id_server::FileEventTracer _tracer;
127  uavcan_posix::dynamic_node_id_server::FileStorageBackend _storage_backend;
128  uavcan_posix::FirmwareVersionChecker _fw_version_checker;
129  uavcan::dynamic_node_id_server::CentralizedServer _server_instance;
130  uavcan_posix::BasicFileServerBackend _fileserver_backend;
131  uavcan::NodeInfoRetriever _node_info_retriever;
132  uavcan::FirmwareUpdateTrigger _fw_upgrade_trigger;
133  uavcan::BasicFileServer _fw_server;
134 
135  /*
136  * The MAVLink parameter bridge needs to know the maximum parameter index
137  * of each node so that clients can determine when parameter listings have
138  * finished. We do that by querying a node's entire parameter set whenever
139  * a parameter message is received for a node with a zero _param_count,
140  * and storing the count here. If a node doesn't respond, or doesn't have
141  * any parameters, its count will stay at zero and we'll try to query the
142  * set again next time.
143  *
144  * The node's UAVCAN ID is used as the index into the _param_counts array.
145  */
146  uint8_t _param_counts[128] = {};
147  bool _count_in_progress = false;
148  uint8_t _count_index = 0;
149 
150  bool _param_in_progress = false;
151  uint8_t _param_index = 0;
152  bool _param_list_in_progress = false;
153  bool _param_list_all_nodes = false;
154  uint8_t _param_list_node_id = 1;
155 
156  uint32_t _param_dirty_bitmap[4] = {};
157  uint8_t _param_save_opcode = 0;
158 
159  bool _cmd_in_progress = false;
160 
161  // uORB topic handle for MAVLink parameter responses
162  orb_advert_t _param_response_pub = nullptr;
163  orb_advert_t _command_ack_pub = nullptr;
164 
165  typedef uavcan::MethodBinder<UavcanServers *,
166  void (UavcanServers::*)(const uavcan::ServiceCallResult<uavcan::protocol::param::GetSet> &)> GetSetCallback;
167  typedef uavcan::MethodBinder<UavcanServers *,
168  void (UavcanServers::*)(const uavcan::ServiceCallResult<uavcan::protocol::param::ExecuteOpcode> &)>
169  ExecuteOpcodeCallback;
170  typedef uavcan::MethodBinder<UavcanServers *,
171  void (UavcanServers::*)(const uavcan::ServiceCallResult<uavcan::protocol::RestartNode> &)> RestartNodeCallback;
172  void cb_getset(const uavcan::ServiceCallResult<uavcan::protocol::param::GetSet> &result);
173  void cb_count(const uavcan::ServiceCallResult<uavcan::protocol::param::GetSet> &result);
174  void cb_opcode(const uavcan::ServiceCallResult<uavcan::protocol::param::ExecuteOpcode> &result);
175  void cb_restart(const uavcan::ServiceCallResult<uavcan::protocol::RestartNode> &result);
176 
177  uavcan::ServiceClient<uavcan::protocol::param::GetSet, GetSetCallback> _param_getset_client;
178  uavcan::ServiceClient<uavcan::protocol::param::ExecuteOpcode, ExecuteOpcodeCallback> _param_opcode_client;
179  uavcan::ServiceClient<uavcan::protocol::RestartNode, RestartNodeCallback> _param_restartnode_client;
180  void param_count(uavcan::NodeID node_id);
181  void param_opcode(uavcan::NodeID node_id);
182 
183  uint8_t get_next_active_node_id(uint8_t base);
184  uint8_t get_next_dirty_node_id(uint8_t base);
185  void set_node_params_dirty(uint8_t node_id) { _param_dirty_bitmap[node_id >> 5] |= 1 << (node_id & 31); }
186  void clear_node_params_dirty(uint8_t node_id) { _param_dirty_bitmap[node_id >> 5] &= ~(1 << (node_id & 31)); }
187  bool are_node_params_dirty(uint8_t node_id) const { return bool((_param_dirty_bitmap[node_id >> 5] >> (node_id & 31)) & 1); }
188 
189  void beep(float frequency);
190 
191  bool _mutex_inited = false;
192  volatile bool _check_fw = false;
193 
194  // ESC enumeration
195  bool _esc_enumeration_active = false;
196  uint8_t _esc_enumeration_ids[uavcan::equipment::esc::RawCommand::FieldTypes::cmd::MaxSize];
197  uint8_t _esc_enumeration_index = 0;
198  uint8_t _esc_count = 0;
199 
200  typedef uavcan::MethodBinder<UavcanServers *,
201  void (UavcanServers::*)(const uavcan::ServiceCallResult<uavcan::protocol::enumeration::Begin> &)>
202  EnumerationBeginCallback;
203  typedef uavcan::MethodBinder<UavcanServers *,
204  void (UavcanServers::*)(const uavcan::ReceivedDataStructure<uavcan::protocol::enumeration::Indication>&)>
205  EnumerationIndicationCallback;
206  void cb_enumeration_begin(const uavcan::ServiceCallResult<uavcan::protocol::enumeration::Begin> &result);
207  void cb_enumeration_indication(const uavcan::ReceivedDataStructure<uavcan::protocol::enumeration::Indication> &msg);
208  void cb_enumeration_getset(const uavcan::ServiceCallResult<uavcan::protocol::param::GetSet> &result);
209  void cb_enumeration_save(const uavcan::ServiceCallResult<uavcan::protocol::param::ExecuteOpcode> &result);
210 
211  uavcan::Publisher<uavcan::equipment::indication::BeepCommand> _beep_pub;
212  uavcan::Subscriber<uavcan::protocol::enumeration::Indication, EnumerationIndicationCallback>
213  _enumeration_indication_sub;
214  uavcan::ServiceClient<uavcan::protocol::enumeration::Begin, EnumerationBeginCallback> _enumeration_client;
215  uavcan::ServiceClient<uavcan::protocol::param::GetSet, GetSetCallback> _enumeration_getset_client;
216  uavcan::ServiceClient<uavcan::protocol::param::ExecuteOpcode, ExecuteOpcodeCallback> _enumeration_save_client;
217 
218  void unpackFwFromROMFS(const char *sd_path, const char *romfs_path);
219  int copyFw(const char *dst, const char *src);
220 };
Objects of this class are owned by the sub-node thread.
Definition: uavcan_virtual_can_driver.hpp:339
Configuration flags used in code.
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
__EXPORT unsigned param_count(void)
Return the total number of parameters.
Definition: parameters.cpp:380
Definition: I2C.hpp:51
This interface defines one method that will be called by the main node thread periodically in order t...
Definition: uavcan_virtual_can_driver.hpp:323
A UAVCAN Server Sub node.
Definition: uavcan_servers.hpp:74
Performance measuring tools.