PixRacer on Blade 130X Helicopter
The ultimate goal of this project is to make a fully autonomous Blade 130X helicopter using PX4 firmware. The autopilot of choice is the PixRacer, because the form-factor is relatively small and it's the next generation pixhawk autopilot.
PixRacer
The autopilot is hard-mounted on a wooden plate, milled by my brother. The plate clamps onto to the tail-boom and a tie-wrap holds it in place. This is by far not the nicest solution, but it's good enough for the prototype. At this point I was still not sure if it was going to work at all. The ESP8266 on top is used for communication with QGroundControl, which works out of the box.
I removed the servo-headers which are normally attached to the PixRacer. I also removed the JST connectors of the servo's and soldered the wires directly to the PixRacer.
Power
The battery is a 2S 450mAh LiPo. The autopilot needs 5V for operation, which is provided by the ACSP5 module which I bought together with the PixRacer. Later I figured out that the servos need 3.8V, which I did not have yet. Because it's still a prototype, I used a small 3A buck converter from ebay to provide power to the servos.
Motor controller
The ESC I used is a Turnigy Plush 12A. I have not yet configured it with BLHeli, but I will need a governor mode at some point. The ESC actually also has a BEC which could be used instead of the ACSP5, but I realized that too late :-p.
RC Transmitter / Receiver
I have some experience with DSMX receivers and transmitters, but for this project I decided to go with FrSky stuff. I have a Turnigy 9X transmitter with a FrSky DJT module. The receiving side is a RX-F802 which I got from banggood. It's hard to find documentation about this module, but apparently it is similar to the RX-F801. If you put a bind plug to connect channels 1 and 3, you will get PPM output on channel 4. This plugs into the RC port of the PixRacer. It's also important to use channel 3 for thrust on the transmitter. The receiver has a built-in failsafe mode, which centers channels 1,2 and 4 and channel 3 to low if the rc link is lost. I started with thrust on channel 1, but if you then switch off the RC and the vehicle is still armed, it will apply half throttle (and pitch backward)!
Firmware
Helicopters are not yet supported by PX4, so I had to do some programming. First I made a new airframe definition in PX4/Firmware/ROMFS/px4fmu_common/init.d
#!nsh
#
# @name Blade 130X
#
# @type Helicopter
#
# @maintainer Bart Slinger <bartslinger@gmail.com>
#
sh /etc/init.d/rc.mc_defaults
set MIXER heli_120deg
To make it visible in QGroundControl, you have to overwrite ~/.config/QGroundControl.org/PX4AirframeFactMetaData.xml with the airframes.xml generated when building PX4 firmware.
I also had to make a new mixer, which was inspired by the CCPM.main.mix mixer. However I found out that the left and right servos had longer arms, so no compensation was needed in the mixer. The ESC is on AUX1, which I control with a turn-knob on my transmitter.
Helicopter 120 degree Cyclic-Collective-Pitch Mixing (CCPM) for PX4FMU
==================================================
Output 0 - Left Servo Mixer
-----------------
Left Servo = Collective (Thurst - 3) - 0.5 * Elevator (Pitch - 1) + 0.866 * Aileron (Roll - 0)
M: 3
O: 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
S: 0 1 -10000 -10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
Output 1 - Front Servo Mixer
----------------
Rear Servo = Collective (Thrust - 3) + Elevator (Pitch - 1)
M: 2
O: 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
S: 0 1 10000 10000 0 -10000 10000
Output 2 - Right Servo Mixer
----------------
Right Servo = Collective (Thurst - 3) - 0.5 * Elevator (Pitch - 1) - 0.866 * Aileron (Roll - 0)
M: 3
O: 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
S: 0 1 -10000 -10000 0 -10000 10000
S: 0 0 -10000 -10000 0 -10000 10000
Output 3 - Tail Servo Mixer
----------------
Tail Servo = Yaw (control index = 2)
M: 1
O: 10000 10000 0 -10000 10000
S: 0 2 10000 10000 0 -10000 10000
Output 4 - Motor speed mixer
-----------------
This would be the motor speed control output from governor power demand- not sure what index to use here?
M: 1
O: 10000 10000 0 -10000 10000
S: 3 5 0 20000 -10000 -10000 10000
The final change needed is in the control law. I did manage to get it flying with the default multicopter controller, but tuning is very hard. To make it easier, I changed to control law to use a direct feed-forward from attitude-error to actuator deflections. In mc_att_control_main.cpp function MulticopterAttitudeControl::control_attitude_rates:
_att_control = _params.rate_p.emult(rates_err) + _params.rate_d.emult(_rates_prev - rates) / dt + _rates_int +
// _params.rate_ff.emult(_rates_sp - _rates_sp_prev) / dt;
_params.rate_ff.emult(_rates_sp);
The final thing is to use the kalman filter, because otherwise attitude estimation is f*cked up with the autopilot hard-mounted to the frame. The EKF2 can be selected in QGroundControl parameters section. It works surprisingly well given the massive vibrations on this thing.