|
| 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 |
0 commit comments