About source code of Ardupilot (ArduPlane)

Hello,

I’m a university student in Japan. I am researching on automatic control of fixed wing UAV, and I want to experiment with Pixhawk.
Specifically, I’m going to add a flight mode based on my control law to the ArduPilot code and load it into Pixhawk through the Mission Planer.
In the control law, inputs (steering angle, thrust) are generated from the state quantities (velocity, angular velocity, position, angle) of the aircraft.

I’m currently reading the code for ArduPilot on github, but I’m struggling because I’m a C++ beginner, the structure is complicated, and the comments aren’t my native language.

The questions I want to ask are
Which header file can be used to obtain the state quantities, and what are the variable’s name?
What variable’s name are used to define the inputs to the aircraft and in which file should it be included?

Thank you

The state is available in the code via the ahrs interface. Look for ‘ahrs’ in the ArduPilot directory and you will see lots of examples of grabbing the state.

In the ArduPlane directory look for ‘nav_roll_cd’, ‘nav_pitch_cd’ and ‘throttle’

Thank your for your advice.

I tried to read the code with the advice. Then I kind of get it.
If I want to get state quantities, should I write like following?

~~~~~~~~~~~~~~~~~~~~~~~~~~

#include <AP_AHRS/AP_AHRS.h>
#include <AP_NavEKF2/AP_NavEKF2.h>

float x = AP_NavEKF2::posNE.x;
float y = AP_NavEKF2::posNE.y;
float z = AP_NavEKF2::posD;
float u = AP_NavEKF2::vel.x;
float v = AP_NavEKF2::vel.y;
float w = AP_NavEKF2::vel.z;
float roll = AP_AHRS::roll_sensor;
float pitch = AP_AHRS::pitch_sensor;
float yaw = AP_AHRS::yaw_sensor;
Vector3f angular velocity = AP_AHRS::gyro_estimate();
Vector3f wind velocity = AP_AHRS::wind_estimate();

~~~~~~~~~~~~~~~~~~~~~~~~~~~

Of course, it is cildish, but is it correct?

close. A few corrections:

for position use

Location loc;
ahrs.get_position(loc);

loc is a global position, with lat, lon in deg*1e7 and altitude in cm.

for earth frame velocity use:

Vector3f vel;
ahrs.get_velocity_NED(vel);

vel will be in m/s.

the attitude eulers are in ahrs.roll, ahrs.pitch, ahrs.yaw, in radians.

1 Like