Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_DAL/AP_DAL.cpp
Views: 1798
#include "AP_DAL.h"12#include <AP_HAL/AP_HAL.h>3#include <AP_Logger/AP_Logger.h>4#include <AP_AHRS/AP_AHRS.h>5#include <AP_Vehicle/AP_Vehicle.h>6#include <AP_OpticalFlow/AP_OpticalFlow.h>7#include <AP_WheelEncoder/AP_WheelEncoder.h>8#include <AP_Vehicle/AP_Vehicle_Type.h>9#include <AP_NavEKF3/AP_NavEKF3_feature.h>10#include <AP_NavEKF/AP_Nav_Common.h>1112#if APM_BUILD_TYPE(APM_BUILD_Replay)13#include <AP_NavEKF2/AP_NavEKF2.h>14#include <AP_NavEKF3/AP_NavEKF3.h>15#endif1617extern const AP_HAL::HAL& hal;1819AP_DAL *AP_DAL::_singleton = nullptr;2021bool AP_DAL::force_write;22bool AP_DAL::logging_started;2324void AP_DAL::start_frame(AP_DAL::FrameType frametype)25{26#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)2728if (!init_done) {29init_sensors();30}3132const AP_AHRS &ahrs = AP::ahrs();3334const uint32_t imu_us = AP::ins().get_last_update_usec();35if (_last_imu_time_us == imu_us) {36_RFRF.frame_types |= uint8_t(frametype);37return;38}39_last_imu_time_us = imu_us;4041// we force write all msgs when logging starts42#if HAL_LOGGING_ENABLED43bool logging = AP::logger().logging_started() && AP::logger().allow_start_ekf();44if (logging && !logging_started) {45force_write = true;46}47logging_started = logging;48#endif4950end_frame();5152_RFRF.frame_types = uint8_t(frametype);5354#if AP_VEHICLE_ENABLED55_RFRH.time_flying_ms = AP::vehicle()->get_time_flying_ms();56#else57_RFRH.time_flying_ms = 0;58#endif59_RFRH.time_us = AP_HAL::micros64();60WRITE_REPLAY_BLOCK(RFRH, _RFRH);6162// update RFRN data63const log_RFRN old = _RFRN;64_RFRN.armed = hal.util->get_soft_armed();65_home = ahrs.get_home();66_RFRN.lat = _home.lat;67_RFRN.lng = _home.lng;68_RFRN.alt = _home.alt;69_RFRN.EAS2TAS = ahrs.get_EAS2TAS();70_RFRN.vehicle_class = (uint8_t)ahrs.get_vehicle_class();71_RFRN.fly_forward = ahrs.get_fly_forward();72_RFRN.takeoff_expected = ahrs.get_takeoff_expected();73_RFRN.touchdown_expected = ahrs.get_touchdown_expected();74_RFRN.ahrs_airspeed_sensor_enabled = ahrs.airspeed_sensor_enabled(ahrs.get_active_airspeed_index());75_RFRN.available_memory = hal.util->available_memory();76_RFRN.ahrs_trim = ahrs.get_trim();77#if AP_OPTICALFLOW_ENABLED78_RFRN.opticalflow_enabled = AP::opticalflow() && AP::opticalflow()->enabled();79#endif80_RFRN.wheelencoder_enabled = AP::wheelencoder() && (AP::wheelencoder()->num_sensors() > 0);81_RFRN.ekf_type = ahrs.get_ekf_type();82WRITE_REPLAY_BLOCK_IFCHANGED(RFRN, _RFRN, old);8384// update body conversion85_rotation_vehicle_body_to_autopilot_body = ahrs.get_rotation_vehicle_body_to_autopilot_body();8687_ins.start_frame();88_baro.start_frame();89_gps.start_frame();90_compass.start_frame();91if (_airspeed) {92_airspeed->start_frame();93}94#if AP_RANGEFINDER_ENABLED95if (_rangefinder) {96_rangefinder->start_frame();97}98#endif99#if AP_BEACON_ENABLED100if (_beacon) {101_beacon->start_frame();102}103#endif104#if HAL_VISUALODOM_ENABLED105if (_visualodom) {106_visualodom->start_frame();107}108#endif109110// populate some derivative values:111_micros = _RFRH.time_us;112_millis = _RFRH.time_us / 1000UL;113114force_write = false;115#endif116}117118// for EKF usage to enable takeoff expected to true119void AP_DAL::set_takeoff_expected()120{121#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)122AP_AHRS &ahrs = AP::ahrs();123ahrs.set_takeoff_expected(true);124#endif125}126127/*128setup optional sensor backends129*/130void AP_DAL::init_sensors(void)131{132init_done = true;133bool alloc_failed = false;134135/*136we only allocate the DAL backends if we had at least one sensor137at the time we startup the EKF138*/139140#if AP_RANGEFINDER_ENABLED141auto *rng = AP::rangefinder();142if (rng && rng->num_sensors() > 0) {143alloc_failed |= (_rangefinder = NEW_NOTHROW AP_DAL_RangeFinder) == nullptr;144}145#endif146147#if AP_AIRSPEED_ENABLED148auto *aspeed = AP::airspeed();149if (aspeed != nullptr && aspeed->get_num_sensors() > 0) {150alloc_failed |= (_airspeed = NEW_NOTHROW AP_DAL_Airspeed) == nullptr;151}152#endif153154#if AP_BEACON_ENABLED155auto *bcn = AP::beacon();156if (bcn != nullptr && bcn->enabled()) {157alloc_failed |= (_beacon = NEW_NOTHROW AP_DAL_Beacon) == nullptr;158}159#endif160161#if HAL_VISUALODOM_ENABLED162auto *vodom = AP::visualodom();163if (vodom != nullptr && vodom->enabled()) {164alloc_failed |= (_visualodom = NEW_NOTHROW AP_DAL_VisualOdom) == nullptr;165}166#endif167168if (alloc_failed) {169AP_BoardConfig::allocation_error("DAL backends");170}171}172173/*174end a frame. Must be called on all events and injections of data (eg175flow) and before starting a new frame176*/177void AP_DAL::end_frame(void)178{179if (_RFRF.frame_types != 0) {180WRITE_REPLAY_BLOCK(RFRF, _RFRF);181_RFRF.frame_types = 0;182}183}184185void AP_DAL::log_event2(AP_DAL::Event event)186{187#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)188end_frame();189struct log_REV2 pkt{190event : uint8_t(event),191};192WRITE_REPLAY_BLOCK(REV2, pkt);193#endif194}195196void AP_DAL::log_SetOriginLLH2(const Location &loc)197{198#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)199struct log_RSO2 pkt{200lat : loc.lat,201lng : loc.lng,202alt : loc.alt,203};204WRITE_REPLAY_BLOCK(RSO2, pkt);205#endif206}207208void AP_DAL::log_writeDefaultAirSpeed2(const float aspeed, const float uncertainty)209{210#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)211struct log_RWA2 pkt{212airspeed: aspeed,213uncertainty: uncertainty,214};215WRITE_REPLAY_BLOCK(RWA2, pkt);216#endif217}218219void AP_DAL::log_event3(AP_DAL::Event event)220{221#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)222end_frame();223struct log_REV3 pkt{224event : uint8_t(event),225};226WRITE_REPLAY_BLOCK(REV3, pkt);227#endif228}229230void AP_DAL::log_SetOriginLLH3(const Location &loc)231{232#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)233struct log_RSO3 pkt{234lat : loc.lat,235lng : loc.lng,236alt : loc.alt,237};238WRITE_REPLAY_BLOCK(RSO3, pkt);239#endif240}241242void AP_DAL::log_writeDefaultAirSpeed3(const float aspeed, const float uncertainty)243{244#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)245struct log_RWA3 pkt{246airspeed: aspeed,247uncertainty: uncertainty248};249WRITE_REPLAY_BLOCK(RWA3, pkt);250#endif251}252253void AP_DAL::log_writeEulerYawAngle(float yawAngle, float yawAngleErr, uint32_t timeStamp_ms, uint8_t type)254{255#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)256struct log_REY3 pkt{257yawangle : yawAngle,258yawangleerr : yawAngleErr,259timestamp_ms : timeStamp_ms,260type : type,261};262WRITE_REPLAY_BLOCK(REY3, pkt);263#endif264}265266int AP_DAL::snprintf(char* str, size_t size, const char *format, ...) const267{268va_list ap;269va_start(ap, format);270int res = hal.util->vsnprintf(str, size, format, ap);271va_end(ap);272return res;273}274275void *AP_DAL::malloc_type(size_t size, MemoryType mem_type) const276{277return hal.util->malloc_type(size, AP_HAL::Util::Memory_Type(mem_type));278}279void AP_DAL::free_type(void *ptr, size_t size, MemoryType mem_type) const280{281return hal.util->free_type(ptr, size, AP_HAL::Util::Memory_Type(mem_type));282}283284// map core number for replay285uint8_t AP_DAL::logging_core(uint8_t c) const286{287#if APM_BUILD_TYPE(APM_BUILD_Replay)288return c+100U;289#else290return c;291#endif292}293294#if HAL_LOGGING_ENABLED295// write out a DAL log message. If old_msg is non-null, then296// only write if the content has changed297void AP_DAL::WriteLogMessage(enum LogMessages msg_type, void *msg, const void *old_msg, uint8_t msg_size)298{299if (!logging_started) {300// we're not logging301return;302}303// we use the _end byte to hold a flag for forcing output304uint8_t &_end = ((uint8_t *)msg)[msg_size];305if (old_msg && !force_write && _end == 0 && memcmp(msg, old_msg, msg_size) == 0) {306// no change, skip this block write307return;308}309if (!AP::logger().WriteReplayBlock(msg_type, msg, msg_size)) {310// mark for forced write next time311_end = 1;312} else {313_end = 0;314}315}316#endif317318/*319check if we are low on CPU for this core. This needs to capture the320timing of running the cores321*/322bool AP_DAL::ekf_low_time_remaining(EKFType etype, uint8_t core)323{324static_assert(MAX_EKF_CORES <= 4, "max 4 EKF cores supported");325const uint8_t mask = (1U<<(core+(uint8_t(etype)*4)));326#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)327/*328if we have used more than 1/3 of the time for a loop then we329return true, indicating that we are low on CPU. This changes the330scheduling of fusion between lanes331*/332const auto &imu = AP::ins();333if ((AP_HAL::micros() - imu.get_last_update_usec())*1.0e-6 > imu.get_loop_delta_t()*0.33) {334_RFRF.core_slow |= mask;335} else {336_RFRF.core_slow &= ~mask;337}338#endif339return (_RFRF.core_slow & mask) != 0;340}341342// log optical flow data343void AP_DAL::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset, float heightOverride)344{345end_frame();346347const log_ROFH old = _ROFH;348_ROFH.rawFlowQuality = rawFlowQuality;349_ROFH.rawFlowRates = rawFlowRates;350_ROFH.rawGyroRates = rawGyroRates;351_ROFH.msecFlowMeas = msecFlowMeas;352_ROFH.posOffset = posOffset;353_ROFH.heightOverride = heightOverride;354WRITE_REPLAY_BLOCK_IFCHANGED(ROFH, _ROFH, old);355}356357// log external navigation data358void AP_DAL::writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms)359{360end_frame();361362const log_REPH old = _REPH;363_REPH.pos = pos;364_REPH.quat = quat;365_REPH.posErr = posErr;366_REPH.angErr = angErr;367_REPH.timeStamp_ms = timeStamp_ms;368_REPH.delay_ms = delay_ms;369_REPH.resetTime_ms = resetTime_ms;370WRITE_REPLAY_BLOCK_IFCHANGED(REPH, _REPH, old);371}372373void AP_DAL::log_SetLatLng(const Location &loc, float posAccuracy, uint32_t timestamp_ms)374{375end_frame();376const log_RSLL old = _RSLL;377_RSLL.lat = loc.lat;378_RSLL.lng = loc.lng;379_RSLL.posAccSD = posAccuracy;380_RSLL.timestamp_ms = timestamp_ms;381WRITE_REPLAY_BLOCK_IFCHANGED(RSLL, _RSLL, old);382}383384// log external velocity data385void AP_DAL::writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms)386{387end_frame();388389const log_REVH old = _REVH;390_REVH.vel = vel;391_REVH.err = err;392_REVH.timeStamp_ms = timeStamp_ms;393_REVH.delay_ms = delay_ms;394WRITE_REPLAY_BLOCK_IFCHANGED(REVH, _REVH, old);395396}397398// log wheel odometry data399void AP_DAL::writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius)400{401end_frame();402403const log_RWOH old = _RWOH;404_RWOH.delAng = delAng;405_RWOH.delTime = delTime;406_RWOH.timeStamp_ms = timeStamp_ms;407_RWOH.posOffset = posOffset;408_RWOH.radius = radius;409WRITE_REPLAY_BLOCK_IFCHANGED(RWOH, _RWOH, old);410}411412void AP_DAL::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset)413{414end_frame();415416const log_RBOH old = _RBOH;417_RBOH.quality = quality;418_RBOH.delPos = delPos;419_RBOH.delAng = delAng;420_RBOH.delTime = delTime;421_RBOH.timeStamp_ms = timeStamp_ms;422WRITE_REPLAY_BLOCK_IFCHANGED(RBOH, _RBOH, old);423}424425#if APM_BUILD_TYPE(APM_BUILD_Replay)426/*427handle frame message. This message triggers the EKF2/EKF3 updates and logging428*/429void AP_DAL::handle_message(const log_RFRF &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)430{431_RFRF.core_slow = msg.core_slow;432433/*434note that we need to handle the case of LOG_REPLAY=1 with435LOG_DISARMED=0. To handle this we need to record the start of the filter436*/437const uint8_t frame_types = msg.frame_types;438if (frame_types & uint8_t(AP_DAL::FrameType::InitialiseFilterEKF2)) {439ekf2_init_done = ekf2.InitialiseFilter();440}441if (frame_types & uint8_t(AP_DAL::FrameType::UpdateFilterEKF2)) {442if (!ekf2_init_done) {443ekf2_init_done = ekf2.InitialiseFilter();444}445if (ekf2_init_done) {446ekf2.UpdateFilter();447}448}449if (frame_types & uint8_t(AP_DAL::FrameType::InitialiseFilterEKF3)) {450ekf3_init_done = ekf3.InitialiseFilter();451}452if (frame_types & uint8_t(AP_DAL::FrameType::UpdateFilterEKF3)) {453if (!ekf3_init_done) {454ekf3_init_done = ekf3.InitialiseFilter();455}456if (ekf3_init_done) {457ekf3.UpdateFilter();458}459}460if (frame_types & uint8_t(AP_DAL::FrameType::LogWriteEKF2)) {461ekf2.Log_Write();462}463if (frame_types & uint8_t(AP_DAL::FrameType::LogWriteEKF3)) {464ekf3.Log_Write();465}466}467468/*469handle optical flow message470*/471void AP_DAL::handle_message(const log_ROFH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)472{473_ROFH = msg;474ekf2.writeOptFlowMeas(msg.rawFlowQuality, msg.rawFlowRates, msg.rawGyroRates, msg.msecFlowMeas, msg.posOffset, msg.heightOverride);475#if EK3_FEATURE_OPTFLOW_FUSION476ekf3.writeOptFlowMeas(msg.rawFlowQuality, msg.rawFlowRates, msg.rawGyroRates, msg.msecFlowMeas, msg.posOffset, msg.heightOverride);477#endif478}479480/*481handle external position data482*/483void AP_DAL::handle_message(const log_REPH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)484{485_REPH = msg;486ekf2.writeExtNavData(msg.pos, msg.quat, msg.posErr, msg.angErr, msg.timeStamp_ms, msg.delay_ms, msg.resetTime_ms);487ekf3.writeExtNavData(msg.pos, msg.quat, msg.posErr, msg.angErr, msg.timeStamp_ms, msg.delay_ms, msg.resetTime_ms);488}489490/*491handle external velocity data492*/493void AP_DAL::handle_message(const log_REVH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)494{495_REVH = msg;496ekf2.writeExtNavVelData(msg.vel, msg.err, msg.timeStamp_ms, msg.delay_ms);497ekf3.writeExtNavVelData(msg.vel, msg.err, msg.timeStamp_ms, msg.delay_ms);498}499500/*501handle wheel odometry data502*/503void AP_DAL::handle_message(const log_RWOH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)504{505_RWOH = msg;506// note that EKF2 does not support wheel odometry507ekf3.writeWheelOdom(msg.delAng, msg.delTime, msg.timeStamp_ms, msg.posOffset, msg.radius);508}509510/*511handle body frame odometry512*/513void AP_DAL::handle_message(const log_RBOH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)514{515_RBOH = msg;516// note that EKF2 does not support body frame odometry517ekf3.writeBodyFrameOdom(msg.quality, msg.delPos, msg.delAng, msg.delTime, msg.timeStamp_ms, msg.delay_ms, msg.posOffset);518}519520/*521handle position reset522*/523void AP_DAL::handle_message(const log_RSLL &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)524{525_RSLL = msg;526// note that EKF2 does not support body frame odometry527const Location loc {msg.lat, msg.lng, 0, Location::AltFrame::ABSOLUTE };528ekf3.setLatLng(loc, msg.posAccSD, msg.timestamp_ms);529}530#endif // APM_BUILD_Replay531532namespace AP {533534AP_DAL &dal()535{536return *AP_DAL::get_singleton();537}538539};540541/*542replay printf. To debug replay failures add rprintf() calls into543EKF2/EKF3 and compare /tmp/replay.log to /tmp/real.log544*/545void rprintf(const char *format, ...)546{547548#if (APM_BUILD_TYPE(APM_BUILD_Replay) || CONFIG_HAL_BOARD == HAL_BOARD_SITL) && CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS549#if APM_BUILD_TYPE(APM_BUILD_Replay)550const char *fname = "/tmp/replay.log";551#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL552const char *fname = "/tmp/real.log";553#endif554static FILE *f;555if (!f) {556f = ::fopen(fname, "w");557}558va_list ap;559va_start(ap, format);560vfprintf(f, format, ap);561fflush(f);562va_end(ap);563#endif564}565566567568