|
PX4 Firmware
PX4 Autopilot Software http://px4.io
|
A UAVCAN node. More...
#include <uavcan_main.hpp>
Public Types | |
| enum | eServerAction : int { None, Start, Stop, CheckFW, Busy } |
| typedef UAVCAN_DRIVER::CanInitHelper< RxQueueLenPerIface > | CanInitHelper |
| typedef uavcan::Node< MemPoolSize > | Node |
| typedef uavcan_stm32::CanInitHelper< RxQueueLenPerIface > | CanInitHelper |
| typedef uavcan::protocol::file::BeginFirmwareUpdate | BeginFirmwareUpdate |
Public Member Functions | |
| UavcanNode (uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) | |
| virtual | ~UavcanNode () |
| virtual int | ioctl (file *filp, int cmd, unsigned long arg) |
| uavcan::Node & | get_node () |
| int | teardown () |
| void | print_info () |
| void | shrink () |
| void | hardpoint_controller_set (uint8_t hardpoint_id, uint16_t command) |
| int | fw_server (eServerAction action) |
| void | attachITxQueueInjector (ITxQueueInjector *injector) |
| int | list_params (int remote_node_id) |
| int | save_params (int remote_node_id) |
| int | set_param (int remote_node_id, const char *name, char *value) |
| int | get_param (int remote_node_id, const char *name) |
| int | reset_node (int remote_node_id) |
| UavcanNode (uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) | |
| virtual | ~UavcanNode () |
| virtual int | ioctl (file *filp, int cmd, unsigned long arg) |
| Node & | get_node () |
| int | teardown () |
| void | print_info () |
Public Member Functions inherited from cdev::CDev | |
| CDev (const char *devname) | |
| Constructor. More... | |
| CDev (const CDev &)=delete | |
| CDev & | operator= (const CDev &)=delete |
| CDev (CDev &&)=delete | |
| CDev & | operator= (CDev &&)=delete |
| virtual | ~CDev () |
| virtual int | init () |
| virtual int | open (file_t *filep) |
| Handle an open of the device. More... | |
| virtual int | close (file_t *filep) |
| Handle a close of the device. More... | |
| virtual ssize_t | read (file_t *filep, char *buffer, size_t buflen) |
| Perform a read from the device. More... | |
| virtual ssize_t | write (file_t *filep, const char *buffer, size_t buflen) |
| Perform a write to the device. More... | |
| virtual off_t | seek (file_t *filep, off_t offset, int whence) |
| Perform a logical seek operation on the device. More... | |
| virtual int | ioctl (file_t *filep, int cmd, unsigned long arg) |
| Perform an ioctl operation on the device. More... | |
| virtual int | poll (file_t *filep, px4_pollfd_struct_t *fds, bool setup) |
| Perform a poll setup/teardown operation. More... | |
| const char * | get_devname () const |
| Get the device name. More... | |
Static Public Member Functions | |
| static int | start (uavcan::NodeID node_id, uint32_t bitrate) |
| static UavcanNode * | instance () |
| static int | getHardwareVersion (uavcan::protocol::HardwareVersion &hwver) |
| static void | busevent_signal_trampoline () |
| static int | start (uavcan::NodeID node_id, uint32_t bitrate) |
| static UavcanNode * | instance () |
Public Attributes | |
| int32_t | active_bitrate |
| uavcan::TimerEventForwarder< void(*)(const uavcan::TimerEvent &)> | _reset_timer |
Protected Member Functions | |
| void | Run () override |
Protected Member Functions inherited from cdev::CDev | |
| virtual pollevent_t | poll_state (file_t *filep) |
| Check the current state of the device for poll events from the perspective of the file. More... | |
| virtual void | poll_notify (pollevent_t events) |
| Report new poll events. More... | |
| virtual void | poll_notify_one (px4_pollfd_struct_t *fds, pollevent_t events) |
| Internal implementation of poll_notify. More... | |
| virtual int | open_first (file_t *filep) |
| Notification of the first open. More... | |
| virtual int | close_last (file_t *filep) |
| Notification of the last close. More... | |
| virtual int | register_class_devname (const char *class_devname) |
| Register a class device name, automatically adding device class instance suffix if need be. More... | |
| virtual int | unregister_class_devname (const char *class_devname, unsigned class_instance) |
| Register a class device name, automatically adding device class instance suffix if need be. More... | |
| void | lock () |
| Take the driver lock. More... | |
| void | unlock () |
| Release the driver lock. More... | |
| int | unregister_driver_and_memory () |
| First, unregisters the driver. More... | |
Private Types | |
| typedef uavcan::MethodBinder< UavcanNode *, void(UavcanNode::*)(const uavcan::TimerEvent &)> | TimerCallback |
| typedef uavcan::MethodBinder< UavcanNode *, void(UavcanNode::*)(const uavcan::ServiceCallResult< uavcan::protocol::param::GetSet > &)> | GetSetCallback |
| typedef uavcan::MethodBinder< UavcanNode *, void(UavcanNode::*)(const uavcan::ServiceCallResult< uavcan::protocol::param::ExecuteOpcode > &)> | ExecuteOpcodeCallback |
| typedef uavcan::MethodBinder< UavcanNode *, void(UavcanNode::*)(const uavcan::ServiceCallResult< uavcan::protocol::RestartNode > &)> | RestartNodeCallback |
| typedef uavcan::MethodBinder< UavcanNode *, void(UavcanNode::*)(const uavcan::ReceivedDataStructure< UavcanNode::BeginFirmwareUpdate::Request > &, uavcan::ServiceResponseDataStructure< UavcanNode::BeginFirmwareUpdate::Response > &)> | BeginFirmwareUpdateCallBack |
Private Member Functions | |
| void | fill_node_info () |
| int | init (uavcan::NodeID node_id, UAVCAN_DRIVER::BusEvent &bus_events) |
| void | node_spin_once () |
| int | start_fw_server () |
| int | stop_fw_server () |
| int | request_fw_check () |
| int | print_params (uavcan::protocol::param::GetSet::Response &resp) |
| int | get_set_param (int nodeid, const char *name, uavcan::protocol::param::GetSet::Request &req) |
| void | update_params () |
| void | set_setget_response (uavcan::protocol::param::GetSet::Response *resp) |
| void | free_setget_response (void) |
| void | enable_idle_throttle_when_armed (bool value) |
| void | handle_time_sync (const uavcan::TimerEvent &) |
| void | cb_setget (const uavcan::ServiceCallResult< uavcan::protocol::param::GetSet > &result) |
| void | cb_opcode (const uavcan::ServiceCallResult< uavcan::protocol::param::ExecuteOpcode > &result) |
| void | cb_restart (const uavcan::ServiceCallResult< uavcan::protocol::RestartNode > &result) |
| void | fill_node_info () |
| int | init (uavcan::NodeID node_id, uavcan_stm32::BusEvent &bus_events) |
| void | node_spin_once () |
| int | run () |
| void | cb_beginfirmware_update (const uavcan::ReceivedDataStructure< UavcanNode::BeginFirmwareUpdate::Request > &req, uavcan::ServiceResponseDataStructure< UavcanNode::BeginFirmwareUpdate::Response > &rsp) |
Static Private Member Functions | |
| static void | busevent_signal_trampoline () |
Private Attributes | |
| px4::atomic_bool | _task_should_exit {false} |
| flag to indicate to tear down the CAN driver More... | |
| px4::atomic< int > | _fw_server_action {None} |
| int | _fw_server_status {-1} |
| bool | _is_armed {false} |
| the arming status of the actuators on the bus More... | |
| unsigned | _output_count {0} |
| number of actuators currently available More... | |
| uavcan_node::Allocator | _pool_allocator |
| uavcan::Node | _node |
| library instance More... | |
| pthread_mutex_t | _node_mutex |
| px4_sem_t | _server_command_sem |
| UavcanEscController | _esc_controller |
| UavcanMixingInterface | _mixing_interface {_node_mutex, _esc_controller} |
| UavcanHardpointController | _hardpoint_controller |
| uavcan::GlobalTimeSyncMaster | _time_sync_master |
| uavcan::GlobalTimeSyncSlave | _time_sync_slave |
| uavcan::NodeStatusMonitor | _node_status_monitor |
| List< IUavcanSensorBridge * > | _sensor_bridges |
| List of active sensor bridges. More... | |
| ITxQueueInjector * | _tx_injector {nullptr} |
| bool | _idle_throttle_when_armed {false} |
| int32_t | _idle_throttle_when_armed_param {0} |
| uORB::Subscription | _parameter_update_sub {ORB_ID(parameter_update)} |
| perf_counter_t | _cycle_perf |
| perf_counter_t | _interval_perf |
| uavcan::TimerEventForwarder< TimerCallback > | _master_timer |
| bool | _callback_success {false} |
| uavcan::protocol::param::GetSet::Response * | _setget_response {nullptr} |
| px4_sem_t | _sem |
| semaphore for scheduling the task More... | |
| int | _task = -1 |
| handle to the OS task More... | |
| bool | _task_should_exit = false |
| flag to indicate to tear down the CAN driver More... | |
| Node | _node |
| library instance More... | |
| uavcan::ServiceServer< BeginFirmwareUpdate, BeginFirmwareUpdateCallBack > | _fw_update_listner |
Static Private Attributes | |
| static constexpr unsigned | MaxBitRatePerSec = 1000000 |
| static constexpr unsigned | bitPerFrame = 148 |
| static constexpr unsigned | FramePerSecond = MaxBitRatePerSec / bitPerFrame |
| static constexpr unsigned | FramePerMSecond = ((FramePerSecond / 1000) + 1) |
| static constexpr unsigned | ScheduleIntervalMs = 3 |
| static constexpr unsigned | RxQueueLenPerIface = FramePerMSecond * ScheduleIntervalMs |
| static UavcanNode * | _instance |
| singleton pointer More... | |
| static constexpr unsigned | MemPoolSize = 2048 |
| static constexpr unsigned | StackSize = 2500 |
Additional Inherited Members | |
Protected Attributes inherited from cdev::CDev | |
| px4_sem_t | _lock |
| lock to protect access to all class members (also for derived classes) More... | |
Static Protected Attributes inherited from cdev::CDev | |
| static const px4_file_operations_t | fops = {} |
| Pointer to the default cdev file operations table; useful for registering clone devices etc. More... | |
A UAVCAN node.
Definition at line 107 of file uavcan_main.hpp.
| typedef uavcan::protocol::file::BeginFirmwareUpdate UavcanNode::BeginFirmwareUpdate |
Definition at line 95 of file uavcannode_main.hpp.
|
private |
Definition at line 139 of file uavcannode_main.hpp.
Definition at line 94 of file uavcannode_main.hpp.
| typedef UAVCAN_DRIVER::CanInitHelper<RxQueueLenPerIface> UavcanNode::CanInitHelper |
Definition at line 132 of file uavcan_main.hpp.
|
private |
Definition at line 231 of file uavcan_main.hpp.
|
private |
Definition at line 229 of file uavcan_main.hpp.
| typedef uavcan::Node<MemPoolSize> UavcanNode::Node |
Definition at line 93 of file uavcannode_main.hpp.
|
private |
Definition at line 233 of file uavcan_main.hpp.
|
private |
Definition at line 221 of file uavcan_main.hpp.
| enum UavcanNode::eServerAction : int |
| Enumerator | |
|---|---|
| None | |
| Start | |
| Stop | |
| CheckFW | |
| Busy | |
Definition at line 133 of file uavcan_main.hpp.
| UavcanNode::UavcanNode | ( | uavcan::ICanDriver & | can_driver, |
| uavcan::ISystemClock & | system_clock | ||
| ) |
Definition at line 78 of file uavcan_main.cpp.
References _node_mutex, and _server_command_sem.
Referenced by start().
|
virtual |
Definition at line 108 of file uavcan_main.cpp.
References _cycle_perf, _instance, _interval_perf, _node_mutex, _sensor_bridges, _server_command_sem, _task_should_exit, fw_server(), perf_free(), and Stop.
| UavcanNode::UavcanNode | ( | uavcan::ICanDriver & | can_driver, |
| uavcan::ISystemClock & | system_clock | ||
| ) |
|
virtual |
|
inline |
Definition at line 156 of file uavcan_main.hpp.
References ToneAlarmInterface::init(), name, UavcanMixingInterface::Run(), and update_params().
|
staticprivate |
|
static |
Definition at line 585 of file uavcan_main.cpp.
References _instance.
Referenced by init(), and signal_callback().
|
private |
Definition at line 265 of file uavcannode_main.cpp.
References App, bootloader_app_shared_write(), bootloader_app_shared_t::bus_speed, cb_reboot(), bootloader_app_shared_t::node_id, and rgb_led().
Referenced by init().
|
private |
Definition at line 187 of file uavcan_main.cpp.
References _callback_success.
Referenced by save_params().
|
private |
Definition at line 220 of file uavcan_main.cpp.
References _callback_success.
Referenced by reset_node().
|
private |
Definition at line 284 of file uavcan_main.cpp.
References _callback_success, and _setget_response.
Referenced by get_set_param().
|
private |
Definition at line 800 of file uavcan_main.cpp.
References _idle_throttle_when_armed, _idle_throttle_when_armed_param, _mixing_interface, UavcanMixingInterface::mixingOutput(), and MixingOutput::setAllMinValues().
Referenced by init(), and Run().
|
private |
|
private |
Definition at line 561 of file uavcan_main.cpp.
References _node, getHardwareVersion(), and px4_firmware_version_string().
Referenced by init().
|
inlineprivate |
Definition at line 181 of file uavcan_main.hpp.
Referenced by get_param(), list_params(), and set_param().
| int UavcanNode::fw_server | ( | eServerAction | action | ) |
Definition at line 480 of file uavcan_main.cpp.
References _fw_server_action, _fw_server_status, _server_command_sem, CheckFW, None, Start, and Stop.
Referenced by uavcan_main(), and ~UavcanNode().
|
inline |
Definition at line 105 of file uavcannode_main.hpp.
References _node, print_info(), and teardown().
|
inline |
Definition at line 143 of file uavcan_main.hpp.
References command.
Referenced by uavcan_main().
| int UavcanNode::get_param | ( | int | remote_node_id, |
| const char * | name | ||
| ) |
Definition at line 385 of file uavcan_main.cpp.
References free_setget_response(), get_set_param(), print_params(), and set_setget_response().
Referenced by uavcan_main().
|
private |
Definition at line 291 of file uavcan_main.cpp.
References _callback_success, _node, cb_setget(), and name.
Referenced by get_param(), list_params(), and set_param().
|
static |
Definition at line 142 of file uavcan_main.cpp.
References instance(), and px4_board_name().
Referenced by fill_node_info(), and UavcanServers::init().
|
private |
Definition at line 674 of file uavcan_main.cpp.
References _node, _time_sync_master, and _time_sync_slave.
Referenced by Run().
| void UavcanNode::hardpoint_controller_set | ( | uint8_t | hardpoint_id, |
| uint16_t | command | ||
| ) |
Definition at line 986 of file uavcan_main.cpp.
References _hardpoint_controller, _node_mutex, and UavcanHardpointController::set_command().
Referenced by uavcan_main().
|
private |
Definition at line 290 of file uavcannode_main.cpp.
References busevent_signal_trampoline(), cb_beginfirmware_update(), ToneAlarmInterface::init(), and OK.
|
private |
Definition at line 594 of file uavcan_main.cpp.
References _esc_controller, _hardpoint_controller, _idle_throttle_when_armed_param, _mixing_interface, _node, _sensor_bridges, busevent_signal_trampoline(), UavcanEscController::DISARMED_OUTPUT_VALUE, enable_idle_throttle_when_armed(), fill_node_info(), UavcanHardpointController::init(), UavcanEscController::init(), ToneAlarmInterface::init(), IUavcanSensorBridge::make_all(), UavcanEscController::max_output_value(), UavcanEscController::MAX_RATE_HZ, UavcanMixingInterface::mixingOutput(), OK, param_find(), param_get(), MixingOutput::setAllDisarmedValues(), MixingOutput::setAllMaxValues(), MixingOutput::setAllMinValues(), and MixingOutput::setMaxTopicUpdateRate().
Referenced by start().
|
inlinestatic |
Definition at line 111 of file uavcannode_main.hpp.
References _instance.
|
inlinestatic |
Definition at line 153 of file uavcan_main.hpp.
Referenced by getHardwareVersion(), uavcan_main(), and uavcannode_main().
|
virtual |
|
virtual |
Definition at line 818 of file uavcan_main.cpp.
References _hardpoint_controller, _mixing_interface, UavcanServers::guessIfAllDynamicNodesAreAllocated(), UavcanServers::instance(), MixingOutput::loadMixerThreadSafe(), cdev::CDev::lock(), MIXERIOCLOADBUF, MIXERIOCRESET, UavcanMixingInterface::mixingOutput(), OK, PWM_SERVO_CLEAR_ARM_OK, PWM_SERVO_SET_ARM_OK, PWM_SERVO_SET_FORCE_SAFETY_OFF, MixingOutput::resetMixerThreadSafe(), UavcanHardpointController::set_command(), UAVCAN_IOCG_NODEID_INPROGRESS, UAVCAN_IOCS_HARDPOINT_SET, and cdev::CDev::unlock().
Referenced by run().
| int UavcanNode::list_params | ( | int | remote_node_id | ) |
Definition at line 253 of file uavcan_main.cpp.
References _callback_success, free_setget_response(), get_set_param(), print_params(), and set_setget_response().
Referenced by uavcan_main().
|
private |
|
private |
Definition at line 659 of file uavcan_main.cpp.
References _node, _tx_injector, and ITxQueueInjector::injectTxFramesInto().
Referenced by RestartRequestHandler::handleRestartRequest(), and Run().
| void UavcanNode::print_info | ( | ) |
| void UavcanNode::print_info | ( | void | ) |
Definition at line 912 of file uavcan_main.cpp.
References _cycle_perf, _interval_perf, _mixing_interface, _node, _node_mutex, _node_status_monitor, _pool_allocator, _sensor_bridges, UavcanMixingInterface::mixingOutput(), perf_print_counter(), and MixingOutput::printStatus().
Referenced by get_node(), run(), uavcan_main(), and uavcannode_main().
|
private |
Definition at line 164 of file uavcan_main.cpp.
Referenced by get_param(), and list_params().
|
private |
Definition at line 439 of file uavcan_main.cpp.
References _fw_server_action, _server_command_sem, Busy, UavcanServers::instance(), None, and UavcanServers::requestCheckAllNodesFirmwareAndUpdate().
Referenced by Run().
| int UavcanNode::reset_node | ( | int | remote_node_id | ) |
Definition at line 229 of file uavcan_main.cpp.
References _callback_success, _node, and cb_restart().
Referenced by uavcan_main().
|
private |
Definition at line 367 of file uavcannode_main.cpp.
References df_bebop_bus_wrapper::_task_should_exit, file, uavcan_stm32::clock::getUtc(), uavcan_stm32::clock::getUtcJumpCount(), uavcan_stm32::clock::getUtcRateCorrectionPPM(), hrt_call_every(), hrt_cancel(), init_indication_controller(), init_sim_controller(), ioctl(), uavcan_stm32::clock::isUtcLocked(), MicroBenchHRT::lock(), OK, print_info(), resources, restart_request_handler, signal_callback(), teardown(), MicroBenchHRT::unlock(), and warnx.
|
overrideprotected |
Definition at line 716 of file uavcan_main.cpp.
References _cycle_perf, _fw_server_action, _fw_server_status, _instance, _interval_perf, _master_timer, _mixing_interface, _node, _node_mutex, _node_status_monitor, _output_count, _parameter_update_sub, _task_should_exit, _time_sync_slave, uavcan_kinetis::clock::adjustUtc(), armed, MixingOutput::armed(), CheckFW, uORB::Subscription::copy(), enable_idle_throttle_when_armed(), handle_time_sync(), hrt_absolute_time(), UavcanMixingInterface::mixingOutput(), node_spin_once(), None, perf_begin(), perf_count(), perf_end(), request_fw_check(), actuator_armed_s::soft_stop, Start, start_fw_server(), Stop, stop_fw_server(), teardown(), MixingOutput::unregister(), update_params(), and uORB::Subscription::updated().
| int UavcanNode::save_params | ( | int | remote_node_id | ) |
Definition at line 196 of file uavcan_main.cpp.
References _callback_success, _node, and cb_opcode().
Referenced by uavcan_main().
| int UavcanNode::set_param | ( | int | remote_node_id, |
| const char * | name, | ||
| char * | value | ||
| ) |
Definition at line 317 of file uavcan_main.cpp.
References f(), free_setget_response(), get_set_param(), math::max(), math::min(), and set_setget_response().
Referenced by uavcan_main().
|
inlineprivate |
Definition at line 180 of file uavcan_main.hpp.
Referenced by get_param(), list_params(), and set_param().
| void UavcanNode::shrink | ( | ) |
Definition at line 978 of file uavcan_main.cpp.
References _node_mutex, and _pool_allocator.
Referenced by uavcan_main().
|
static |
|
static |
Definition at line 505 of file uavcan_main.cpp.
References _instance, init(), ll40ls::instance, OK, ScheduleIntervalMs, and UavcanNode().
Referenced by uavcan_main(), and uavcannode_start().
|
private |
Definition at line 412 of file uavcan_main.cpp.
References _fw_server_action, _node, _server_command_sem, _tx_injector, UavcanServers::attachITxQueueInjector(), Busy, UavcanServers::instance(), None, and UavcanServers::start().
Referenced by Run().
|
private |
Definition at line 456 of file uavcan_main.cpp.
References _fw_server_action, _server_command_sem, _tx_injector, Busy, UavcanServers::instance(), None, and UavcanServers::stop().
Referenced by Run().
| int UavcanNode::teardown | ( | ) |
| int UavcanNode::teardown | ( | ) |
Definition at line 811 of file uavcan_main.cpp.
References _server_command_sem.
Referenced by get_node(), run(), and Run().
|
private |
Definition at line 406 of file uavcan_main.cpp.
References _mixing_interface.
Referenced by Run().
|
private |
Definition at line 224 of file uavcan_main.hpp.
Referenced by cb_opcode(), cb_restart(), cb_setget(), get_set_param(), list_params(), reset_node(), and save_params().
|
private |
Definition at line 216 of file uavcan_main.hpp.
Referenced by print_info(), Run(), and ~UavcanNode().
|
private |
Definition at line 200 of file uavcan_main.hpp.
Referenced by init(), UavcanMixingInterface::mixerChanged(), and UavcanMixingInterface::updateOutputs().
|
private |
Definition at line 186 of file uavcan_main.hpp.
Referenced by fw_server(), request_fw_check(), Run(), start_fw_server(), and stop_fw_server().
|
private |
Definition at line 187 of file uavcan_main.hpp.
Referenced by fw_server(), and Run().
|
private |
Definition at line 141 of file uavcannode_main.hpp.
|
private |
Definition at line 202 of file uavcan_main.hpp.
Referenced by hardpoint_controller_set(), init(), and ioctl().
|
private |
Definition at line 211 of file uavcan_main.hpp.
Referenced by enable_idle_throttle_when_armed().
|
private |
Definition at line 212 of file uavcan_main.hpp.
Referenced by enable_idle_throttle_when_armed(), and init().
|
staticprivate |
singleton pointer
Definition at line 193 of file uavcan_main.hpp.
Referenced by busevent_signal_trampoline(), instance(), Run(), start(), and ~UavcanNode().
|
private |
Definition at line 217 of file uavcan_main.hpp.
Referenced by print_info(), Run(), and ~UavcanNode().
|
private |
the arming status of the actuators on the bus
Definition at line 189 of file uavcan_main.hpp.
|
private |
Definition at line 222 of file uavcan_main.hpp.
Referenced by Run().
|
private |
Definition at line 201 of file uavcan_main.hpp.
Referenced by enable_idle_throttle_when_armed(), init(), ioctl(), print_info(), Run(), and update_params().
|
private |
library instance
Definition at line 132 of file uavcannode_main.hpp.
|
private |
library instance
Definition at line 197 of file uavcan_main.hpp.
Referenced by fill_node_info(), get_node(), get_set_param(), handle_time_sync(), init(), node_spin_once(), print_info(), reset_node(), Run(), save_params(), and start_fw_server().
|
private |
Definition at line 198 of file uavcan_main.hpp.
Referenced by hardpoint_controller_set(), print_info(), UavcanMixingInterface::Run(), Run(), shrink(), UavcanNode(), and ~UavcanNode().
|
private |
Definition at line 205 of file uavcan_main.hpp.
Referenced by print_info(), and Run().
|
private |
number of actuators currently available
Definition at line 191 of file uavcan_main.hpp.
Referenced by Run().
|
private |
Definition at line 214 of file uavcan_main.hpp.
Referenced by Run().
|
private |
Definition at line 195 of file uavcan_main.hpp.
Referenced by print_info(), and shrink().
| uavcan::TimerEventForwarder<void (*)(const uavcan::TimerEvent &)> UavcanNode::_reset_timer |
Definition at line 149 of file uavcannode_main.hpp.
|
private |
semaphore for scheduling the task
Definition at line 127 of file uavcannode_main.hpp.
|
private |
List of active sensor bridges.
Definition at line 207 of file uavcan_main.hpp.
Referenced by init(), print_info(), and ~UavcanNode().
|
private |
Definition at line 199 of file uavcan_main.hpp.
Referenced by fw_server(), request_fw_check(), start_fw_server(), stop_fw_server(), teardown(), UavcanNode(), and ~UavcanNode().
|
private |
Definition at line 226 of file uavcan_main.hpp.
Referenced by cb_setget().
|
private |
handle to the OS task
Definition at line 128 of file uavcannode_main.hpp.
|
private |
flag to indicate to tear down the CAN driver
Definition at line 129 of file uavcannode_main.hpp.
|
private |
flag to indicate to tear down the CAN driver
Definition at line 185 of file uavcan_main.hpp.
Referenced by Run(), and ~UavcanNode().
|
private |
Definition at line 203 of file uavcan_main.hpp.
Referenced by handle_time_sync().
|
private |
Definition at line 204 of file uavcan_main.hpp.
Referenced by handle_time_sync(), and Run().
|
private |
Definition at line 209 of file uavcan_main.hpp.
Referenced by node_spin_once(), start_fw_server(), and stop_fw_server().
| int32_t UavcanNode::active_bitrate |
Definition at line 116 of file uavcannode_main.hpp.
|
staticprivate |
Definition at line 110 of file uavcan_main.hpp.
|
staticprivate |
Definition at line 112 of file uavcan_main.hpp.
|
staticprivate |
Definition at line 111 of file uavcan_main.hpp.
|
staticprivate |
Definition at line 109 of file uavcan_main.hpp.
|
staticprivate |
Definition at line 71 of file uavcannode_main.hpp.
|
staticprivate |
Definition at line 129 of file uavcan_main.hpp.
|
staticprivate |
Definition at line 114 of file uavcan_main.hpp.
Referenced by start().
|
staticprivate |
Definition at line 90 of file uavcannode_main.hpp.