CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Compass/AP_Compass_DroneCAN.cpp
Views: 1798
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_Compass_DroneCAN.h"
17
18
#if AP_COMPASS_DRONECAN_ENABLED
19
20
#include <AP_HAL/AP_HAL.h>
21
22
#include <AP_CANManager/AP_CANManager.h>
23
#include <AP_DroneCAN/AP_DroneCAN.h>
24
#include <AP_BoardConfig/AP_BoardConfig.h>
25
#include <AP_Logger/AP_Logger.h>
26
#include <SITL/SITL.h>
27
28
extern const AP_HAL::HAL& hal;
29
30
#define LOG_TAG "COMPASS"
31
32
AP_Compass_DroneCAN::DetectedModules AP_Compass_DroneCAN::_detected_modules[];
33
HAL_Semaphore AP_Compass_DroneCAN::_sem_registry;
34
35
AP_Compass_DroneCAN::AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint32_t devid) :
36
_devid(devid)
37
{
38
}
39
40
bool AP_Compass_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
41
{
42
const auto driver_index = ap_dronecan->get_driver_index();
43
44
return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field, driver_index) != nullptr)
45
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_2, driver_index) != nullptr)
46
#if AP_COMPASS_DRONECAN_HIRES_ENABLED
47
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_hires, driver_index) != nullptr)
48
#endif
49
;
50
}
51
52
AP_Compass_Backend* AP_Compass_DroneCAN::probe(uint8_t index)
53
{
54
AP_Compass_DroneCAN* driver = nullptr;
55
if (!_detected_modules[index].driver && _detected_modules[index].ap_dronecan) {
56
WITH_SEMAPHORE(_sem_registry);
57
// Register new Compass mode to a backend
58
driver = NEW_NOTHROW AP_Compass_DroneCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].devid);
59
if (driver) {
60
if (!driver->init()) {
61
delete driver;
62
return nullptr;
63
}
64
_detected_modules[index].driver = driver;
65
AP::can().log_text(AP_CANManager::LOG_INFO,
66
LOG_TAG,
67
"Found Mag Node %d on Bus %d Sensor ID %d\n",
68
_detected_modules[index].node_id,
69
_detected_modules[index].ap_dronecan->get_driver_index(),
70
_detected_modules[index].sensor_id);
71
#if AP_TEST_DRONECAN_DRIVERS
72
// Scroll through the registered compasses, and set the offsets
73
if (driver->_compass.get_offsets(index).is_zero()) {
74
driver->_compass.set_offsets(index, AP::sitl()->mag_ofs[index]);
75
}
76
77
// we want to simulate a calibrated compass by default, so set
78
// scale to 1
79
AP_Param::set_default_by_name("COMPASS_SCALE", 1);
80
AP_Param::set_default_by_name("COMPASS_SCALE2", 1);
81
AP_Param::set_default_by_name("COMPASS_SCALE3", 1);
82
driver->save_dev_id(index);
83
driver->set_rotation(index, ROTATION_NONE);
84
85
// make first compass external
86
driver->set_external(index, true);
87
#endif
88
}
89
}
90
return driver;
91
}
92
93
bool AP_Compass_DroneCAN::init()
94
{
95
// Adding 1 is necessary to allow backward compatibility, where this field was set as 1 by default
96
if (!register_compass(_devid, _instance)) {
97
return false;
98
}
99
100
set_dev_id(_instance, _devid);
101
set_external(_instance, true);
102
103
AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "AP_Compass_DroneCAN loaded\n\r");
104
return true;
105
}
106
107
AP_Compass_DroneCAN* AP_Compass_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id)
108
{
109
if (ap_dronecan == nullptr) {
110
return nullptr;
111
}
112
for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {
113
if (_detected_modules[i].driver &&
114
_detected_modules[i].ap_dronecan == ap_dronecan &&
115
_detected_modules[i].node_id == node_id &&
116
_detected_modules[i].sensor_id == sensor_id) {
117
return _detected_modules[i].driver;
118
}
119
}
120
121
bool already_detected = false;
122
// Check if there's an empty spot for possible registration
123
for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) {
124
if (_detected_modules[i].ap_dronecan == ap_dronecan &&
125
_detected_modules[i].node_id == node_id &&
126
_detected_modules[i].sensor_id == sensor_id) {
127
// Already Detected
128
already_detected = true;
129
break;
130
}
131
}
132
if (!already_detected) {
133
for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) {
134
if (nullptr == _detected_modules[i].ap_dronecan) {
135
_detected_modules[i].ap_dronecan = ap_dronecan;
136
_detected_modules[i].node_id = node_id;
137
_detected_modules[i].sensor_id = sensor_id;
138
_detected_modules[i].devid = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN,
139
ap_dronecan->get_driver_index(),
140
node_id,
141
sensor_id + 1); // we use sensor_id as devtype
142
break;
143
}
144
}
145
}
146
147
struct DetectedModules tempslot;
148
// Sort based on the node_id, larger values first
149
// we do this, so that we have repeatable compass
150
// registration, especially in cases of extraneous
151
// CAN compass is connected.
152
for (uint8_t i = 1; i < COMPASS_MAX_BACKEND; i++) {
153
for (uint8_t j = i; j > 0; j--) {
154
if (_detected_modules[j].node_id > _detected_modules[j-1].node_id) {
155
tempslot = _detected_modules[j];
156
_detected_modules[j] = _detected_modules[j-1];
157
_detected_modules[j-1] = tempslot;
158
}
159
}
160
}
161
return nullptr;
162
}
163
164
void AP_Compass_DroneCAN::handle_mag_msg(const Vector3f &mag)
165
{
166
Vector3f raw_field = mag * 1000.0;
167
168
accumulate_sample(raw_field, _instance);
169
}
170
171
void AP_Compass_DroneCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg)
172
{
173
WITH_SEMAPHORE(_sem_registry);
174
175
Vector3f mag_vector;
176
AP_Compass_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, 0);
177
if (driver != nullptr) {
178
mag_vector[0] = msg.magnetic_field_ga[0];
179
mag_vector[1] = msg.magnetic_field_ga[1];
180
mag_vector[2] = msg.magnetic_field_ga[2];
181
driver->handle_mag_msg(mag_vector);
182
}
183
}
184
185
void AP_Compass_DroneCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg)
186
{
187
WITH_SEMAPHORE(_sem_registry);
188
189
Vector3f mag_vector;
190
uint8_t sensor_id = msg.sensor_id;
191
AP_Compass_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, sensor_id);
192
if (driver != nullptr) {
193
mag_vector[0] = msg.magnetic_field_ga[0];
194
mag_vector[1] = msg.magnetic_field_ga[1];
195
mag_vector[2] = msg.magnetic_field_ga[2];
196
driver->handle_mag_msg(mag_vector);
197
}
198
}
199
200
#if AP_COMPASS_DRONECAN_HIRES_ENABLED
201
/*
202
just log hires magnetic field data for magnetic surveying
203
*/
204
void AP_Compass_DroneCAN::handle_magnetic_field_hires(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer,
205
const dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes &msg)
206
{
207
// @LoggerMessage: MAGH
208
// @Description: Magnetometer high resolution data
209
// @Field: TimeUS: Time since system startup
210
// @Field: Node: CAN node
211
// @Field: Sensor: sensor ID on node
212
// @Field: Bus: CAN bus
213
// @Field: Mx: X axis field
214
// @Field: My: y axis field
215
// @Field: Mz: z axis field
216
217
#if HAL_LOGGING_ENABLED
218
// just log it for now
219
AP::logger().WriteStreaming("MAGH", "TimeUS,Node,Sensor,Bus,Mx,My,Mz", "s#-----", "F------", "QBBBfff",
220
transfer.timestamp_usec,
221
transfer.source_node_id,
222
ap_dronecan->get_driver_index(),
223
msg.sensor_id,
224
msg.magnetic_field_ga[0]*1000,
225
msg.magnetic_field_ga[1]*1000,
226
msg.magnetic_field_ga[2]*1000);
227
#endif // HAL_LOGGING_ENABLED
228
}
229
#endif // AP_COMPASS_DRONECAN_HIRES_ENABLED
230
231
void AP_Compass_DroneCAN::read(void)
232
{
233
drain_accumulated_samples(_instance);
234
}
235
#endif // AP_COMPASS_DRONECAN_ENABLED
236
237