Browse Source

Conditional inclusion of the Node Allocation and FW Server - default is OFF

sbg
David Sidrane 10 years ago committed by Lorenz Meier
parent
commit
3e64ad10e8
  1. 25
      src/modules/uavcan/uavcan_main.cpp
  2. 21
      src/modules/uavcan/uavcan_main.hpp

25
src/modules/uavcan/uavcan_main.cpp

@ -53,14 +53,15 @@ @@ -53,14 +53,15 @@
#include <drivers/drv_pwm_output.h>
#include "uavcan_main.hpp"
#include <uavcan_posix/dynamic_node_id_server/file_event_tracer.hpp>
#include <uavcan_posix/dynamic_node_id_server/file_storage_backend.hpp>
#include <uavcan_posix/firmware_version_checker.hpp>
#if defined(USE_FW_NODE_SERVER)
# include <uavcan_posix/dynamic_node_id_server/file_event_tracer.hpp>
# include <uavcan_posix/dynamic_node_id_server/file_storage_backend.hpp>
# include <uavcan_posix/firmware_version_checker.hpp>
//todo:The Inclusion of file_server_backend is killing
// #include <sys/types.h> and leaving OK undefined
#define OK 0
# define OK 0
#endif
/**
* @file uavcan_main.cpp
@ -75,20 +76,26 @@ @@ -75,20 +76,26 @@
* UavcanNode
*/
UavcanNode *UavcanNode::_instance;
#if defined(USE_FW_NODE_SERVER)
uavcan::dynamic_node_id_server::CentralizedServer *UavcanNode::_server_instance;
uavcan_posix::dynamic_node_id_server::FileEventTracer tracer;
uavcan_posix::dynamic_node_id_server::FileStorageBackend storage_backend;
uavcan_posix::FirmwareVersionChecker fw_version_checker;
#endif
UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) :
CDev("uavcan", UAVCAN_DEVICE_PATH),
_node(can_driver, system_clock),
_node_mutex(),
#if !defined(USE_FW_NODE_SERVER)
_esc_controller(_node)
#else
_esc_controller(_node),
_fileserver_backend(_node),
_node_info_retriever(_node),
_fw_upgrade_trigger(_node, fw_version_checker),
_fw_server(_node, _fileserver_backend)
#endif
{
_control_topics[0] = ORB_ID(actuator_controls_0);
_control_topics[1] = ORB_ID(actuator_controls_1);
@ -154,7 +161,10 @@ UavcanNode::~UavcanNode() @@ -154,7 +161,10 @@ UavcanNode::~UavcanNode()
perf_free(_perfcnt_node_spin_elapsed);
perf_free(_perfcnt_esc_mixer_output_elapsed);
perf_free(_perfcnt_esc_mixer_total_elapsed);
#if defined(USE_FW_NODE_SERVER)
delete(_server_instance);
#endif
}
@ -305,7 +315,7 @@ int UavcanNode::init(uavcan::NodeID node_id) @@ -305,7 +315,7 @@ int UavcanNode::init(uavcan::NodeID node_id)
br = br->getSibling();
}
#if defined(USE_FW_NODE_SERVER)
/* Initialize the fw version checker.
* giving it it's path
*/
@ -373,6 +383,7 @@ int UavcanNode::init(uavcan::NodeID node_id) @@ -373,6 +383,7 @@ int UavcanNode::init(uavcan::NodeID node_id)
return ret;
}
#endif
/* Start the Node */
return _node.start();

21
src/modules/uavcan/uavcan_main.hpp

@ -34,6 +34,7 @@ @@ -34,6 +34,7 @@
#pragma once
#include <nuttx/config.h>
#include <uavcan_stm32/uavcan_stm32.hpp>
#include <drivers/device/device.h>
#include <systemlib/perf_counter.h>
@ -47,13 +48,13 @@ @@ -47,13 +48,13 @@
#include "actuators/esc.hpp"
#include "sensors/sensor_bridge.hpp"
#include <uavcan/protocol/dynamic_node_id_server/centralized.hpp>
#include <uavcan/protocol/node_info_retriever.hpp>
#include <uavcan_posix/basic_file_server_backend.hpp>
#include <uavcan/protocol/firmware_update_trigger.hpp>
#include <uavcan/protocol/file_server.hpp>
#if defined(USE_FW_NODE_SERVER)
# include <uavcan/protocol/dynamic_node_id_server/centralized.hpp>
# include <uavcan/protocol/node_info_retriever.hpp>
# include <uavcan_posix/basic_file_server_backend.hpp>
# include <uavcan/protocol/firmware_update_trigger.hpp>
# include <uavcan/protocol/file_server.hpp>
#endif
/**
* @file uavcan_main.hpp
@ -147,7 +148,6 @@ private: @@ -147,7 +148,6 @@ private:
unsigned _output_count = 0; ///< number of actuators currently available
static UavcanNode *_instance; ///< singleton pointer
static uavcan::dynamic_node_id_server::CentralizedServer *_server_instance; ///< server singleton pointer
Node _node; ///< library instance
pthread_mutex_t _node_mutex;
@ -155,11 +155,14 @@ private: @@ -155,11 +155,14 @@ private:
UavcanEscController _esc_controller;
#if defined(USE_FW_NODE_SERVER)
static uavcan::dynamic_node_id_server::CentralizedServer *_server_instance; ///< server singleton pointer
uavcan_posix::BasicFileSeverBackend _fileserver_backend;
uavcan::NodeInfoRetriever _node_info_retriever;
uavcan::FirmwareUpdateTrigger _fw_upgrade_trigger;
uavcan::BasicFileServer _fw_server;
#endif
List<IUavcanSensorBridge *> _sensor_bridges; ///< List of active sensor bridges
MixerGroup *_mixers = nullptr;

Loading…
Cancel
Save