37 #include "uavcan_driver.hpp" 38 #include <drivers/device/device.h> 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> 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> 59 #include "uavcan_module.hpp" 60 #include "uavcan_virtual_can_driver.hpp" 76 static constexpr
unsigned NumIfaces = 1;
78 static constexpr
unsigned StackSize = 6000;
79 static constexpr
unsigned Priority = 120;
81 static constexpr
unsigned VirtualIfaceBlockAllocationQuota = 80;
83 static constexpr
float BeepFrequencyGenericIndication = 1000.0F;
84 static constexpr
float BeepFrequencySuccess = 2000.0F;
85 static constexpr
float BeepFrequencyError = 100.0F;
92 static int start(uavcan::INode &main_node);
95 uavcan::SubNode<> &get_node() {
return _subnode; }
104 void attachITxQueueInjector(
ITxQueueInjector **injector) {*injector = &_vdriver;}
106 void requestCheckAllNodesFirmwareAndUpdate() { _check_fw =
true; }
108 bool guessIfAllDynamicNodesAreAllocated() {
return _server_instance.guessIfAllDynamicNodesAreAllocated(); }
111 pthread_t _subnode_thread;
112 pthread_mutex_t _subnode_mutex;
113 volatile bool _subnode_thread_should_exit =
false;
117 pthread_addr_t run(pthread_addr_t);
123 uavcan::SubNode<> _subnode;
124 uavcan::INode &_main_node;
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;
146 uint8_t _param_counts[128] = {};
147 bool _count_in_progress =
false;
148 uint8_t _count_index = 0;
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;
156 uint32_t _param_dirty_bitmap[4] = {};
157 uint8_t _param_save_opcode = 0;
159 bool _cmd_in_progress =
false;
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);
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;
181 void param_opcode(uavcan::NodeID node_id);
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); }
189 void beep(
float frequency);
191 bool _mutex_inited =
false;
192 volatile bool _check_fw =
false;
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;
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);
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;
218 void unpackFwFromROMFS(
const char *sd_path,
const char *romfs_path);
219 int copyFw(
const char *dst,
const char *src);
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
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.