Problem with AP_InertialSensor in Pixhawk 2.1 (CubeBlack)

Hi all

Just wanted to report a problem that I am having with my CubeBlack (Pixhawk 2.1). Not sure if that is the expected behaviour, which I don’t think it should but here it goes.

For reference, I am using the examples AHRS_Test.cpp and INS_generic.cpp as a basis. Moreover, I am compiling everything in Ubuntu 20.04 LTS (WSL - Windows 10), and building/uploading with “./waf build --targets examples/INS_generic --upload” after having configured the board with “./waf configure --board CubeBlack”. I am then visualising the port output with Arduino and Putty.

Here is the problem.

First of all, the INS_generic.cpp doesn’t run at all whereas the AHRS_test.cpp code does. So I went and check why, and here is the main difference that I found which need to be clarified as to why it needs to operate in that way, and if appropriate corrected for INS_generic at the very least.

Reducing INS_generic.cpp code down to a bare minimum (Hello world type of code) before crashing looks something like this:

--------------------- INS_generic.cpp ----------------------
#include <AP_HAL/AP_HAL.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
static AP_InertialSensor ins;
#if HAL_EXTERNAL_AHRS_ENABLED
static AP_ExternalAHRS eAHRS;
#endif // HAL_EXTERNAL_AHRS_ENABLED
static AP_BoardConfig BoardConfig;
void setup(void);
void loop(void);
void setup(void)
{
BoardConfig.init();
hal.console->printf(“AP_InertialSensor startup…\n”);
ins.init(100); //<--------- Remove this lane and it will run normally.
}
void loop(void){
hal.console->printf(“Hello world!\n”);
hal.scheduler->delay(1000);
}
AP_HAL_MAIN();
--------------------- INS_generic.cpp ----------------------

Like it says there, remove the ins.init(100) lane, and the code will run fine, just doing what it is supposed to do. Include it, and the code does absolutely nothing. The COM port hangs and freezes the application that you are using to visualise it, eg. Arduino or Putty.

Similarly, reducing AHRS_Test.cpp code down to a bare working minimum looks something like this:

--------------------- AHRS_Test.cpp ----------------------
#include <AP_AHRS/AP_AHRS.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <GCS_MAVLink/GCS_Dummy.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup();
void loop();
AP_Int32 logger_bitmask;
static AP_Logger logger{logger_bitmask};
class DummyVehicle : public AP_Vehicle {
public:
AP_AHRS_NavEKF ahrs{AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
bool set_mode(const uint8_t new_mode, const ModeReason reason) override { return true; };
uint8_t get_mode() const override { return 1; };
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) override {};
void init_ardupilot() override {};
void load_parameters() override {};
void init() {
BoardConfig.init();
ins.init(100);
}
};
static DummyVehicle vehicle;
void setup(void){
vehicle.init();
}
void loop(void){
hal.console->printf(“Hello world!\n”);
hal.scheduler->delay(1000);
}
AP_HAL_MAIN();
--------------------- AHRS_Test.cpp ----------------------

So basically, the only difference is that the BoardConfig and INS are initialised inside the DummyVehicle/AP_Vehicle class. I don’t understand why is this required for the CubeBlack and I think it should be clearly stated why this is required to operate in this way in the CubeBlack.

On the other hand, I can confirm that the INS_generic.cpp code works perfectly fine as it is in a Pixhawk 2.4.8. It is just in the CubeBlack that I am getting this problem.

I hope someone can help me understand if this is the desired way of operating, or if it is indeed a problem and how to correct it.

Thank you for your attention.

Regards,
Oscar

I am pretty the difference has nothing to do with the example code (as we don’t test them often or in the CI, they are ofter broken) but in CubeBlack board definition. CubeBlack got some hardware safety that check that all 3 IMU are up and working on boot. I am pretty that it s the root cause of the issue there.

Hi there

Thank you for your prompt response.

Doesn’t Pixhawk 2.4.8 have 2 IMUs? In that case, it would also do some checks for those ones. Not sure what I am missing here.

I just would like to get this to work as I am learning ArduPilot and I am looking to use it extensively for my research for next 3 years or so, but one of the first tasks that I need to do will be to build my own flight controller code top to bottom, including whatever modes and checks are relevant/required to have a clear understanding of the inner working of my code, as well as to have the flexibility to change whatever I deemed necessary, eg. estimation and control algorithms, communication with other computing boards, communication with my own Labview-based GCS, and so on. And I cannot particularly achieve that if the most basi examples, available in the main website (https://ardupilot.org/dev/docs/learning-ardupilot-the-example-sketches.html) are not working.

I understand if other examples are not necessarily kept as checked as this ones. So again, I would appreciate if someone could instruct why it should be done through the AP_Vehicle class, and why it cannot be done directly as in the INS_generic example, or if possible, how to do it directly.

Thanks again.

Regards,
Oscar