An issue in the build sitl of the custom controller

Hello everybody!
I’m having an issue with my custom controller. Can someone help me?

I followed the tutorial, based on @Emre_Saldiran’s work to implement my controller, an LQR controller.

[Adding Custom Attitude Controller to Copter — Dev documentation]

However, in the step of placing the input and output arguments I had to add a library to declare.
P.S. I needed the twelve states of the quadcopter, and I was missing a vector for the position, I know I could integrate the velocity rate but I thought that since I already had a file that took the position, I should just do the same thing I did with the attitude , speed and gyro (I will attach the figure).

I added the AP_InertialNav library to the CustomControl’s backend (it’s an existing library in the ardupilot code, that is, I didn’t create a new one) and added it to all files in the AC_CustomControl folder. (Figure below)

However, when I run "./waf configure --board sitl --debug copter " I get the following message (figure below):

customcontroller_problem1

Note: I can build normally on the board outside of sitl, using " ./waf configure --board fmuv3 " and " ./waf copter "

What may be the problem?
Thanks for all the help in advance!

Hi @Luana_Teodosio ,

I am glad you are interested in custom controller implementation.

You are getting this error because custom controller constructor input list doesn’t match with how it is created in Arducopter files(Copter.h).

If you also change ArduCopter/Copter.h line 473 so that it takes inertial nav library as input, it should compile.

Please let me know how it goes.

Emre

Yes,thanks for the solution, I was able to build after I followed your solution.

So I compiled and simulated and debugged. However, I got the following message:

How can I solve this problem and if the problem is the position what other library can I get the position data to use as my copter state?

Another unrelated question, how can I get the copter model used by ardupilot to use in math software?

Once again, thank you

There is a detailed ArduCopter simulink model in the ArduPilot source code repository.

1 Like

Segmentation faults can happen for a number reasons.

First, can you define pos_real like this?

const Vector3f &pos_real = _inav.get_position_neu_cm()

and access “pos_real” values like this

pos_real.x

Second, Can you also do a full clean build? Run “./waf clean” and build again.

You can also feed current as an input argument to the backend update function and but since you already compiled this way it shouldn’t be necessary.

Yes, you were right about defining pos_real that way:
const Vector3f &pos_real = _inav->get_position_neu_cm()

I just had to change . for ->

I did run ./waf clean and I managed to build again. However, during the simulation with the debug it stopped when getting the values of pos_real. (See figure below)

I call the position values:
float arg_rate_pos[3]{ pos_real.x, pos_real.y, pos_real.z };

I see you are using Simulink code generation. Can you share the branch you are working on?

Sure! my_branch, the AC_LQR folder is where the Simulink generated code and AC_CustomControl_LF is my custom controller.

It’s something simple. As the LQR is basically a gain matrix, it has 4 input vectors each with 3 states + 1 feedback input vector with the 12 states and the output

You can use AHRS library that is already present within the custom controller to access the current position and velocity by adding the following lines into the update function.

    Vector3f current_position;
    Vector3f current_velocity;
    // This is only added to avoid getting ignored return warning
    // EKF always returns true, so this doesn't affect us.
    if (_ahrs->get_relative_position_NED_origin(current_position) && _ahrs->get_velocity_NED(current_velocity)) {}

Ok! Thank you for suggestion!!