Skip to content

Commit 2ab0328

Browse files
committed
add AP_InertialSensor_DRONECAN
1 parent 2a3dc4b commit 2ab0328

File tree

7 files changed

+231
-8
lines changed

7 files changed

+231
-8
lines changed

libraries/AP_DroneCAN/AP_DroneCAN.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@
4040
#include <AP_GPS/AP_GPS.h>
4141
#include <AP_BattMonitor/AP_BattMonitor_DroneCAN.h>
4242
#include <AP_Compass/AP_Compass_DroneCAN.h>
43+
#include <AP_InertialSensor/AP_InertialSensor_DRONECAN.h>
4344
#include <AP_Airspeed/AP_Airspeed_DroneCAN.h>
4445
#include <AP_Proximity/AP_Proximity_DroneCAN.h>
4546
#include <SRV_Channel/SRV_Channel.h>
@@ -359,6 +360,9 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters)
359360
}
360361

361362
// Roundup all subscribers from supported drivers
363+
#if AP_INS_DRONECAN_ENABLED
364+
AP_InertialSensor_DRONECAN::subscribe_msgs(this);
365+
#endif
362366
#if AP_GPS_DRONECAN_ENABLED
363367
AP_GPS_DroneCAN::subscribe_msgs(this);
364368
#endif

libraries/AP_InertialSensor/AP_InertialSensor.cpp

Lines changed: 23 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
#include "AP_InertialSensor_Invensensev3.h"
4040
#include "AP_InertialSensor_NONE.h"
4141
#include "AP_InertialSensor_SCHA63T.h"
42+
#include "AP_InertialSensor_DRONECAN.h"
4243

4344
/* Define INS_TIMING_DEBUG to track down scheduling issues with the main loop.
4445
* Output is on the debug console. */
@@ -681,6 +682,15 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
681682
// @User: Advanced
682683
AP_GROUPINFO("_RAW_LOG_OPT", 56, AP_InertialSensor, raw_logging_options, 0),
683684

685+
#if AP_INS_DRONECAN_ENABLED
686+
// @Param: _DRONECAN_HITL
687+
// @DisplayName: DroneCAN HITL IMU option
688+
// @Description: DroneCAN uavcan.equipment.ahrs.RawIMU subscriber: enable or disable
689+
// @Bitmask: 0:Disable, 1:Enable
690+
// @User: Advanced
691+
AP_GROUPINFO("_DRONECAN", 57, AP_InertialSensor, dronecan_hitl, 0),
692+
#endif
693+
684694
/*
685695
NOTE: parameter indexes have gaps above. When adding new
686696
parameters check for conflicts carefully
@@ -1172,6 +1182,12 @@ AP_InertialSensor::detect_backends(void)
11721182
}
11731183
#endif
11741184

1185+
#if AP_INS_DRONECAN_ENABLED
1186+
if (dronecan_hitl == 1 && AP_InertialSensor_DRONECAN::instances_amount == 0) {
1187+
ADD_BACKEND(new AP_InertialSensor_DRONECAN(*this));
1188+
}
1189+
#endif
1190+
11751191
#if AP_SIM_INS_ENABLED
11761192
for (uint8_t i=0; i<AP::sitl()->imu_count; i++) {
11771193
ADD_BACKEND(AP_InertialSensor_SITL::detect(*this, i==1?INS_SITL_SENSOR_B:INS_SITL_SENSOR_A));
@@ -1552,26 +1568,26 @@ MAV_RESULT AP_InertialSensor::calibrate_trim()
15521568
/*
15531569
check if the accelerometers are calibrated in 3D and that current number of accels matched number when calibrated
15541570
*/
1555-
bool AP_InertialSensor::accel_calibrated_ok_all() const
1571+
int8_t AP_InertialSensor::accel_calibrated_ok_all() const
15561572
{
15571573
// check each accelerometer has offsets saved
15581574
for (uint8_t i=0; i<get_accel_count(); i++) {
15591575
if (!_accel_id_ok[i]) {
1560-
return false;
1576+
return -1;
15611577
}
15621578
// exactly 0.0 offset is extremely unlikely
15631579
if (_accel_offset(i).get().is_zero()) {
1564-
return false;
1580+
return -2;
15651581
}
15661582
// zero scaling also indicates not calibrated
15671583
if (_accel_scale(i).get().is_zero()) {
1568-
return false;
1584+
return -3;
15691585
}
15701586
}
15711587
for (uint8_t i=get_accel_count(); i<INS_MAX_INSTANCES; i++) {
15721588
if (_accel_id(i) != 0) {
15731589
// missing accel
1574-
return false;
1590+
return -4;
15751591
}
15761592
}
15771593

@@ -1582,13 +1598,13 @@ bool AP_InertialSensor::accel_calibrated_ok_all() const
15821598
bool have_scaling = (!is_zero(scaling.x) && !is_equal(scaling.x,1.0f)) || (!is_zero(scaling.y) && !is_equal(scaling.y,1.0f)) || (!is_zero(scaling.z) && !is_equal(scaling.z,1.0f));
15831599
bool have_offsets = !_accel_offset(i).get().is_zero();
15841600
if (have_scaling || have_offsets) {
1585-
return false;
1601+
return -5;
15861602
}
15871603
}
15881604
}
15891605

15901606
// if we got this far the accelerometers must have been calibrated
1591-
return true;
1607+
return 1;
15921608
}
15931609

15941610
// return true if accel instance should be used (must be healthy and have it's use parameter set to 1)

libraries/AP_InertialSensor/AP_InertialSensor.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,7 @@ class AP_InertialSensor : AP_AccelCal_Client
147147
bool get_accel_health(void) const { return get_accel_health(_primary_accel); }
148148
bool get_accel_health_all(void) const;
149149
uint8_t get_accel_count(void) const { return MIN(INS_MAX_INSTANCES, _accel_count); }
150-
bool accel_calibrated_ok_all() const;
150+
int8_t accel_calibrated_ok_all() const;
151151
bool use_accel(uint8_t instance) const;
152152

153153
// get observed sensor rates, including any internal sampling multiplier
@@ -794,6 +794,8 @@ class AP_InertialSensor : AP_AccelCal_Client
794794
bool raw_logging_option_set(RAW_LOGGING_OPTION option) const {
795795
return (raw_logging_options.get() & int32_t(option)) != 0;
796796
}
797+
798+
AP_Int16 dronecan_hitl;
797799
};
798800

799801
namespace AP {

libraries/AP_InertialSensor/AP_InertialSensor_Backend.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -129,6 +129,7 @@ class AP_InertialSensor_Backend
129129
DEVTYPE_INS_ICM42670 = 0x3A,
130130
DEVTYPE_INS_ICM45686 = 0x3B,
131131
DEVTYPE_INS_SCHA63T = 0x3C,
132+
DEVTYPE_INS_UAVCAN = 0x3D,
132133
};
133134

134135
protected:
Lines changed: 164 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,164 @@
1+
/*
2+
* This file is free software: you can redistribute it and/or modify it
3+
* under the terms of the GNU General Public License as published by the
4+
* Free Software Foundation, either version 3 of the License, or
5+
* (at your option) any later version.
6+
*
7+
* This file is distributed in the hope that it will be useful, but
8+
* WITHOUT ANY WARRANTY; without even the implied warranty of
9+
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10+
* See the GNU General Public License for more details.
11+
*
12+
* You should have received a copy of the GNU General Public License along
13+
* with this program. If not, see <http://www.gnu.org/licenses/>.
14+
*/
15+
#include <AP_HAL/AP_HAL.h>
16+
#include "AP_InertialSensor_DRONECAN.h"
17+
18+
#if AP_INS_DRONECAN_ENABLED
19+
20+
#include <AP_BoardConfig/AP_BoardConfig.h>
21+
#include <GCS_MAVLink/GCS.h>
22+
#include <GCS_MAVLink/GCS_MAVLink.h>
23+
24+
extern const AP_HAL::HAL& hal;
25+
uint8_t AP_InertialSensor_DRONECAN::instances_amount = 0;
26+
AP_InertialSensor_DRONECAN::DetectedModules AP_InertialSensor_DRONECAN::_detected_modules[] = {0};
27+
static uint32_t imu_ts_ms = 0;
28+
static uint32_t max_timeout_ms = 0;
29+
static size_t msg_counter{0};
30+
31+
void AP_InertialSensor_DRONECAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
32+
{
33+
if (ap_dronecan == nullptr) {
34+
return;
35+
}
36+
37+
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_raw_imu, ap_dronecan->get_driver_index()) == nullptr) {
38+
AP_BoardConfig::allocation_error("imu_sub");
39+
}
40+
}
41+
42+
AP_InertialSensor_DRONECAN::AP_InertialSensor_DRONECAN(AP_InertialSensor &imu)
43+
: AP_InertialSensor_Backend(imu)
44+
{
45+
_detected_modules[0].driver = this;
46+
instances_amount++;
47+
}
48+
49+
bool AP_InertialSensor_DRONECAN::init()
50+
{
51+
return true;
52+
}
53+
54+
void AP_InertialSensor_DRONECAN::start()
55+
{
56+
static uint8_t bus_id = 0;
57+
uint32_t gyro_id = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN, bus_id, 1, DEVTYPE_INS_UAVCAN); // 3997955
58+
uint32_t accel_id = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN, bus_id, 2, DEVTYPE_INS_UAVCAN); // 3998211
59+
bus_id++;
60+
const float rate = 300;
61+
if (_imu.register_gyro(_detected_modules[0].gyro_instance, rate, gyro_id) && _imu.register_accel(_detected_modules[0].accel_instance, rate, accel_id)) {
62+
started = true;
63+
}
64+
set_gyro_orientation(_detected_modules[0].gyro_instance, ROTATION_NONE);
65+
set_accel_orientation(_detected_modules[0].accel_instance, ROTATION_NONE);
66+
GCS_SEND_TEXT(MAV_SEVERITY_WARNING,
67+
"Use DroneCAN HITL IMU: gyro=%lu accel=%lu.",
68+
(long unsigned int)gyro_id,
69+
(long unsigned int)accel_id
70+
);
71+
if (_imu.get_accel_count() != 1 || !_imu.accel_calibrated_ok_all()) {
72+
GCS_SEND_TEXT(MAV_SEVERITY_ERROR,
73+
"Wrong HITL Accel setup: num=%lu calib_res=%i.",
74+
(long unsigned int)_imu.get_accel_count(),
75+
(int8_t)_imu.accel_calibrated_ok_all()
76+
);
77+
}
78+
if (_imu.get_accel_count() != 1 || !_imu.gyro_calibrated_ok_all()) {
79+
GCS_SEND_TEXT(MAV_SEVERITY_ERROR,
80+
"Wrong HITL Gyro setup: num=%lu calib_res=%i.",
81+
(long unsigned int)_imu.get_gyro_count(),
82+
(int8_t)_imu.gyro_calibrated_ok_all()
83+
);
84+
}
85+
86+
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_DRONECAN::loop, void),
87+
"UC_IMU",
88+
1024, AP_HAL::Scheduler::PRIORITY_BOOST, 1)) {
89+
AP_HAL::panic("AP_InertialSensor_DRONECAN: Failed to create thread");
90+
}
91+
}
92+
93+
void AP_InertialSensor_DRONECAN::loop()
94+
{
95+
while (true) {
96+
hal.scheduler->delay_microseconds(5000);
97+
if (imu_ts_ms == 0 || imu_ts_ms + 100 < AP_HAL::millis()) {
98+
Vector3f accel{0.00f, 0.00f, -9.81f};
99+
Vector3f gyro{0.00f, 0.00f, 0.00f};
100+
publish_accel(accel);
101+
publish_gyro(gyro);
102+
}
103+
104+
static uint32_t logger_next_time_ms = 10000;
105+
if (AP_HAL::millis() > logger_next_time_ms) {
106+
logger_next_time_ms = AP_HAL::millis() + 10000;
107+
GCS_SEND_TEXT(MAV_SEVERITY_INFO,
108+
"Hitl IMU: %lu msg/sec, max timeout=%lu ms.",
109+
(long unsigned int)(msg_counter / 10),
110+
(long unsigned int)(max_timeout_ms)
111+
);
112+
msg_counter = 0;
113+
max_timeout_ms = 0;
114+
}
115+
}
116+
}
117+
118+
bool AP_InertialSensor_DRONECAN::update()
119+
{
120+
if (started) {
121+
update_accel(_detected_modules[0].accel_instance);
122+
update_gyro(_detected_modules[0].gyro_instance);
123+
}
124+
return started;
125+
}
126+
127+
void AP_InertialSensor_DRONECAN::publish_accel(Vector3f& accel)
128+
{
129+
_rotate_and_correct_accel(_detected_modules[0].accel_instance, accel);
130+
_notify_new_accel_raw_sample(_detected_modules[0].accel_instance, accel);
131+
}
132+
133+
void AP_InertialSensor_DRONECAN::publish_gyro(Vector3f& gyro)
134+
{
135+
_rotate_and_correct_gyro(_detected_modules[0].gyro_instance, gyro);
136+
_notify_new_gyro_raw_sample(_detected_modules[0].gyro_instance, gyro);
137+
}
138+
139+
void AP_InertialSensor_DRONECAN::handle_raw_imu(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_RawIMU &msg)
140+
{
141+
if (_detected_modules[0].driver == nullptr) {
142+
return;
143+
}
144+
145+
msg_counter++;
146+
max_timeout_ms = AP_HAL::millis() - imu_ts_ms;
147+
imu_ts_ms = AP_HAL::millis();
148+
149+
Vector3f accel{
150+
msg.accelerometer_latest[0],
151+
msg.accelerometer_latest[1],
152+
msg.accelerometer_latest[2]
153+
};
154+
_detected_modules[0].driver->publish_accel(accel);
155+
156+
Vector3f gyro{
157+
msg.rate_gyro_latest[0],
158+
msg.rate_gyro_latest[1],
159+
msg.rate_gyro_latest[2]
160+
};
161+
_detected_modules[0].driver->publish_gyro(gyro);
162+
}
163+
164+
#endif
Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
#pragma once
2+
#include "AP_InertialSensor_config.h"
3+
4+
#if AP_INS_DRONECAN_ENABLED
5+
#include "AP_InertialSensor.h"
6+
#include "AP_InertialSensor_Backend.h"
7+
#include <AP_DroneCAN/AP_DroneCAN.h>
8+
9+
class AP_InertialSensor_DRONECAN : public AP_InertialSensor_Backend {
10+
public:
11+
AP_InertialSensor_DRONECAN(AP_InertialSensor &imu);
12+
bool update() override;
13+
void start() override;
14+
void publish_accel(Vector3f& accel);
15+
void publish_gyro(Vector3f& gyro);
16+
static uint8_t instances_amount;
17+
18+
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
19+
static void handle_raw_imu(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_RawIMU &msg);
20+
21+
private:
22+
bool init();
23+
void loop(void);
24+
bool started;
25+
// Module Detection Registry
26+
static struct DetectedModules {
27+
AP_InertialSensor_DRONECAN *driver;
28+
uint8_t gyro_instance;
29+
uint8_t accel_instance;
30+
} _detected_modules[1];
31+
};
32+
#endif

libraries/AP_InertialSensor/AP_InertialSensor_config.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,3 +63,7 @@
6363
#ifndef AP_INERTIALSENSOR_KILL_IMU_ENABLED
6464
#define AP_INERTIALSENSOR_KILL_IMU_ENABLED 1
6565
#endif
66+
67+
#ifndef AP_INS_DRONECAN_ENABLED
68+
#define AP_INS_DRONECAN_ENABLED (HAL_ENABLE_DRONECAN_DRIVERS)
69+
#endif

0 commit comments

Comments
 (0)