APM:Libraries
AP_Compass_UAVCAN.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #include <AP_HAL/AP_HAL.h>
17 
18 #if HAL_WITH_UAVCAN
19 
20 #include "AP_Compass_UAVCAN.h"
21 
22 #if HAL_OS_POSIX_IO
23 #include <sys/types.h>
24 #include <sys/stat.h>
25 #include <fcntl.h>
26 #include <unistd.h>
27 #endif
28 
31 
32 extern const AP_HAL::HAL& hal;
33 
34 #define debug_mag_uavcan(level, fmt, args...) do { if ((level) <= AP_BoardConfig_CAN::get_can_debug()) { printf(fmt, ##args); }} while (0)
35 
36 /*
37  constructor - registers instance at top Compass driver
38  */
40  AP_Compass_Backend(compass)
41 {
42  _mag_baro = hal.util->new_semaphore();
43 }
44 
46 {
47  if (_initialized)
48  {
49  if (hal.can_mgr[_manager] != nullptr) {
50  AP_UAVCAN *ap_uavcan = hal.can_mgr[_manager]->get_UAVCAN();
51  if (ap_uavcan != nullptr) {
52  ap_uavcan->remove_mag_listener(this);
53 
54  debug_mag_uavcan(2, "AP_Compass_UAVCAN destructed\n\r");
55  }
56  }
57  }
58 }
59 
61 {
62  AP_Compass_UAVCAN *sensor = nullptr;
63 
64  if (AP_BoardConfig_CAN::get_can_num_ifaces() != 0) {
65  for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
66  if (hal.can_mgr[i] != nullptr) {
67  AP_UAVCAN *uavcan = hal.can_mgr[i]->get_UAVCAN();
68  if (uavcan != nullptr) {
69  uint8_t freemag = uavcan->find_smallest_free_mag_node();
70  if (freemag != UINT8_MAX) {
71  sensor = new AP_Compass_UAVCAN(compass);
72  if (sensor->register_uavcan_compass(i, freemag)) {
73  debug_mag_uavcan(2, "AP_Compass_UAVCAN probed, drv: %d, node: %d\n\r", i, freemag);
74  return sensor;
75  } else {
76  delete sensor;
77  sensor = nullptr;
78  }
79  }
80  }
81  }
82  }
83  }
84 
85  return sensor;
86 }
87 
88 bool AP_Compass_UAVCAN::register_uavcan_compass(uint8_t mgr, uint8_t node)
89 {
90  if (hal.can_mgr[mgr] != nullptr) {
91  AP_UAVCAN *ap_uavcan = hal.can_mgr[mgr]->get_UAVCAN();
92  if (ap_uavcan != nullptr) {
93  _manager = mgr;
94 
95  if (ap_uavcan->register_mag_listener_to_node(this, node)) {
96  _instance = register_compass();
97 
98  struct DeviceStructure {
99  uint8_t bus_type : 3;
100  uint8_t bus: 5;
101  uint8_t address;
102  uint8_t devtype;
103  };
104  union DeviceId {
105  struct DeviceStructure devid_s;
106  uint32_t devid;
107  };
108  union DeviceId d;
109 
110  d.devid_s.bus_type = 3;
111  d.devid_s.bus = mgr;
112  d.devid_s.address = node;
113  d.devid_s.devtype = 1;
114 
115  set_dev_id(_instance, d.devid);
116  set_external(_instance, true);
117 
118  _sum.zero();
119  _count = 0;
120 
121  accumulate();
122 
123  debug_mag_uavcan(2, "AP_Compass_UAVCAN loaded\n\r");
124 
125  return true;
126  }
127  }
128  }
129 
130  return false;
131 }
132 
133 void AP_Compass_UAVCAN::read(void)
134 {
135  // avoid division by zero if we haven't received any mag reports
136  if (_count == 0) {
137  return;
138  }
139 
140  if (_mag_baro->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
141  _sum /= _count;
142 
143  publish_filtered_field(_sum, _instance);
144 
145  _sum.zero();
146  _count = 0;
147  _mag_baro->give();
148  }
149 }
150 
152 {
153  Vector3f raw_field = mag * 1000.0;
154 
155  // rotate raw_field from sensor frame to body frame
156  rotate_field(raw_field, _instance);
157 
158  // publish raw_field (uncorrected point sample) for calibration use
159  publish_raw_field(raw_field, _instance);
160 
161  // correct raw_field for known errors
162  correct_field(raw_field, _instance);
163 
164  if (_mag_baro->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
165  // accumulate into averaging filter
166  _sum += raw_field;
167  _count++;
168  _mag_baro->give();
169  }
170 }
171 
172 #endif
void set_external(uint8_t instance, bool external)
bool register_uavcan_compass(uint8_t mgr, uint8_t node)
static AP_Compass_Backend * probe(Compass &compass)
void rotate_field(Vector3f &mag, uint8_t instance)
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
void correct_field(Vector3f &mag, uint8_t i)
AP_HAL::Util * util
Definition: HAL.h:115
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual Semaphore * new_semaphore(void)
Definition: Util.h:108
void set_dev_id(uint8_t instance, uint32_t dev_id)
AP_HAL::CANManager ** can_mgr
Definition: HAL.h:120
void remove_mag_listener(AP_Compass_Backend *rem_listener)
uint8_t register_compass(void) const
uint8_t find_smallest_free_mag_node()
uint8_t register_mag_listener_to_node(AP_Compass_Backend *new_listener, uint8_t node)
static Compass compass
Definition: AHRS_Test.cpp:20
AP_Compass_UAVCAN(Compass &compass)
virtual void accumulate(void)
~AP_Compass_UAVCAN() override
void publish_raw_field(const Vector3f &mag, uint8_t instance)
void handle_mag_msg(Vector3f &mag)
void read(void) override