PX4 Firmware
PX4 Autopilot Software http://px4.io
uavcanesc_main.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2015 PX4 Development Team. All rights reserved.
4  * Author: Pavel Kirienko <pavel.kirienko@gmail.com>
5  * David Sidrane <david_s5@nscdg.com>
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * 1. Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * 2. Redistributions in binary form must reproduce the above copyright
14  * notice, this list of conditions and the following disclaimer in
15  * the documentation and/or other materials provided with the
16  * distribution.
17  * 3. Neither the name PX4 nor the names of its contributors may be
18  * used to endorse or promote products derived from this software
19  * without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
28  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
29  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  ****************************************************************************/
35 
36 #pragma once
37 
38 #include <px4_platform_common/px4_config.h>
40 #include <drivers/device/device.h>
41 #include <uavcan/protocol/file/BeginFirmwareUpdate.hpp>
42 #include <uavcan/node/timer.hpp>
43 /**
44  *
45  * Defines functionality of UAVCAN ESC node.
46  */
47 
48 #define NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN 1
49 #define UAVCAN_DEVICE_PATH "/dev/uavcan/esc"
50 
51 // we add 1 to allow for busevent
52 #define UAVCAN_NUM_POLL_FDS (NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN+1)
53 
54 /**
55  * A UAVCAN node.
56  */
57 class UavcanEsc : public cdev::CDev
58 {
59  /*
60  * This memory is reserved for uavcan to use as over flow for message
61  * Coming from multiple sources that my not be considered at development
62  * time.
63  *
64  * The call to getNumFreeBlocks will tell how many blocks there are
65  * free -and multiply it times getBlockSize to get the number of bytes
66  *
67  */
68  static constexpr unsigned MemPoolSize = 2048;
69 
70  /*
71  * This memory is reserved for uavcan to use for queuing CAN frames.
72  * At 1Mbit there is approximately one CAN frame every 200 uS.
73  * The number of buffers sets how long you can go without calling
74  * node_spin_xxxx. Since our task is the only one running and the
75  * driver will light the fd when there is a CAN frame we can nun with
76  * a minimum number of buffers to conserver memory. Each buffer is
77  * 32 bytes. So 5 buffers costs 160 bytes and gives us a maximum required
78  * poll rate of ~1 mS
79  *
80  */
81  static constexpr unsigned RxQueueLenPerIface = 5;
82 
83  /*
84  * This memory is uses for the tasks stack size
85  */
86 
87  static constexpr unsigned StackSize = 4096;
88 
89 public:
90  typedef uavcan::Node<MemPoolSize> Node;
92  typedef uavcan::protocol::file::BeginFirmwareUpdate BeginFirmwareUpdate;
93 
94  UavcanEsc(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock);
95 
96  virtual ~UavcanEsc();
97 
98  virtual int ioctl(file *filp, int cmd, unsigned long arg);
99 
100  static int start(uavcan::NodeID node_id, uint32_t bitrate);
101 
102  Node &get_node() { return _node; }
103 
104  int teardown();
105 
106  void print_info();
107 
108  static UavcanEsc *instance() { return _instance; }
109 
110 
111  /* The bit rate that can be passed back to the bootloader */
112 
113  int32_t active_bitrate;
114 
115 
116 private:
117  void fill_node_info();
118  int init(uavcan::NodeID node_id, uavcan_stm32::BusEvent &bus_events);
119  void node_spin_once();
120  int run();
121  static void busevent_signal_trampoline();
122 
123 
124  px4_sem_t _sem; ///< semaphore for scheduling the task
125  int _task = -1; ///< handle to the OS task
126  bool _task_should_exit = false; ///< flag to indicate to tear down the CAN driver
127 
128  static UavcanEsc *_instance; ///< singleton pointer
129  Node _node; ///< library instance
130  pthread_mutex_t _node_mutex;
131 
132  typedef uavcan::MethodBinder<UavcanEsc *,
133  void (UavcanEsc::*)(const uavcan::ReceivedDataStructure<UavcanEsc::BeginFirmwareUpdate::Request> &,
134  uavcan::ServiceResponseDataStructure<UavcanEsc::BeginFirmwareUpdate::Response> &)>
136 
137  uavcan::ServiceServer<BeginFirmwareUpdate, BeginFirmwareUpdateCallBack> _fw_update_listner;
138  void cb_beginfirmware_update(const uavcan::ReceivedDataStructure<UavcanEsc::BeginFirmwareUpdate::Request> &req,
139  uavcan::ServiceResponseDataStructure<UavcanEsc::BeginFirmwareUpdate::Response> &rsp);
140 
141 public:
142 
143  /* A timer used to reboot after the response is sent */
144 
145  uavcan::TimerEventForwarder<void (*)(const uavcan::TimerEvent &)> _reset_timer;
146 
147 };
uavcan::ServiceServer< BeginFirmwareUpdate, BeginFirmwareUpdateCallBack > _fw_update_listner
uavcan::protocol::file::BeginFirmwareUpdate BeginFirmwareUpdate
UavcanEsc(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock)
uavcan::Node< MemPoolSize > Node
Helper class.
Definition: can.hpp:291
uavcan_stm32::CanInitHelper< RxQueueLenPerIface > CanInitHelper
virtual int init()
Definition: CDev.cpp:119
static constexpr unsigned MemPoolSize
void node_spin_once()
void print_info()
static int start(uavcan::NodeID node_id, uint32_t bitrate)
Abstract class for any character device.
Definition: CDev.hpp:58
Node _node
library instance
static void busevent_signal_trampoline()
uavcan::MethodBinder< UavcanEsc *, void(UavcanEsc::*)(const uavcan::ReceivedDataStructure< UavcanEsc::BeginFirmwareUpdate::Request > &, uavcan::ServiceResponseDataStructure< UavcanEsc::BeginFirmwareUpdate::Response > &)> BeginFirmwareUpdateCallBack
virtual int ioctl(file *filp, int cmd, unsigned long arg)
static constexpr unsigned RxQueueLenPerIface
uavcan::TimerEventForwarder< void(*)(const uavcan::TimerEvent &)> _reset_timer
static UavcanEsc * _instance
singleton pointer
int32_t active_bitrate
void cb_beginfirmware_update(const uavcan::ReceivedDataStructure< UavcanEsc::BeginFirmwareUpdate::Request > &req, uavcan::ServiceResponseDataStructure< UavcanEsc::BeginFirmwareUpdate::Response > &rsp)
static constexpr unsigned StackSize
struct @83::@85::@87 file
static UavcanEsc * instance()
virtual ~UavcanEsc()
pthread_mutex_t _node_mutex
int _task
handle to the OS task
bool _task_should_exit
flag to indicate to tear down the CAN driver
void fill_node_info()
A UAVCAN node.
px4_sem_t _sem
semaphore for scheduling the task
Node & get_node()