Hello,
It might be a bit late but I faced the same issue as you and I managed to get my rover working with a ZK-5AD and a Pixhawk 2.4.8. (though it also works for other Pixhawk versions like Pixhawk 6X). It does require a bit of work, but it’s within anyone’s reach. You just need to create a new mode which you could call, for example, ZK-5AD. Here you can find information on creating a mode in ArduPilot: Rover: Adding a New Drive Mode — Dev documentation. However, be careful with Mission Planner, the information is not up to date. You should not modify the ParameterMetaDataBackup.xml
file but the rover.apm.pdef.xml
file. I’ve made a comment about this on a forum: New Flight Mode not shown in Mission Planner - #17 by sylv.
Once all this is done, you just need to create a file that will be your new mode (e.g., mode_ZK5AD.cpp)
#include “Rover.h”
void ModeZK5AD::update() {
// fetch roll and pitch inputs
int16_t roll_out = RC_Channels::rc_channel(0)->get_radio_in();
int16_t pitch_out = RC_Channels::rc_channel(1)->get_radio_in();
// ZK-5AD Drive Logic Table
if (pitch_out > 1500 + _TRIM) { // MOVE FORWARD
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MOVE FORWARD");
SRV_Channels::set_output_pwm_chan(_AUX_OUT1 ,_HIGH); //AUX_OUT1
SRV_Channels::set_output_pwm_chan(_AUX_OUT2, _LOW);//AUX_OUT2
SRV_Channels::set_output_pwm_chan(_AUX_OUT3, _HIGH); //AUX_OUT3
SRV_Channels::set_output_pwm_chan(_AUX_OUT4, _LOW); //AUX_OUT4
} else if (pitch_out < 1500 - _TRIM) { // MOVE BACK
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MOVE BACK");
SRV_Channels::set_output_pwm_chan(_AUX_OUT1, _LOW);
SRV_Channels::set_output_pwm_chan(_AUX_OUT2, _HIGH);
SRV_Channels::set_output_pwm_chan(_AUX_OUT3, _LOW);
SRV_Channels::set_output_pwm_chan(_AUX_OUT4, _HIGH);
} else if (abs(pitch_out - 1500) <= _TRIM) { // TURN RIGHT
if (roll_out > 1500 + _TRIM) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TURN RIGHT");
SRV_Channels::set_output_pwm_chan(_AUX_OUT1, _LOW);
SRV_Channels::set_output_pwm_chan(_AUX_OUT2, _HIGH);
SRV_Channels::set_output_pwm_chan(_AUX_OUT3, _HIGH);
SRV_Channels::set_output_pwm_chan(_AUX_OUT4, _LOW);
} else if (roll_out < 1500 - _TRIM) { // TURN LEFT
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TURN LEFT");
SRV_Channels::set_output_pwm_chan(_AUX_OUT1, _HIGH);
SRV_Channels::set_output_pwm_chan(_AUX_OUT2, _LOW);
SRV_Channels::set_output_pwm_chan(_AUX_OUT3, _LOW);
SRV_Channels::set_output_pwm_chan(_AUX_OUT4, _HIGH);
} else { // STOP
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "STOP");
SRV_Channels::set_output_pwm_chan(_AUX_OUT1, _LOW);
SRV_Channels::set_output_pwm_chan(_AUX_OUT2, _LOW);
SRV_Channels::set_output_pwm_chan(_AUX_OUT3, _LOW);
SRV_Channels::set_output_pwm_chan(_AUX_OUT4, _LOW);
}
}
}
And in the mode.h file, you can declare the class as follows:
class ModeZK5AD : public Mode {
public:
uint32_t mode_number() const override {
return ZK5AD;
}
const char *name4() const override {
return "ZK5AD";
}
// methods that affect movement of the vehicle in this mode
void update() override;
private:
// constants
const int _HIGH = 2000;
const int _LOW = 1000;
const int _TRIM = 10;
const int _AUX_OUT1 = 8;
const int _AUX_OUT2 = 9;
const int _AUX_OUT3 = 10;
const int _AUX_OUT4 = 11;
};
The D0, D1, D2, and D3 inputs of the ZK-5AD are connected respectively to the AUX_OUT1, AUX_OUT2, AUX_OUT3, and AUX_OUT4 signal line outputs of the Pixhawk. Make sure to also connect the ground lines.
The last very important thing to do is to change the SERVO_RATE parameter value. By default, it’s set to 50Hz with the Rover, but the output signal is too weak to control the ZK-5AD driver card. You need to change the value from 50 to 400. As a result, your output voltage will change from 0.25V to 2.65V. (because it’s a PWM signal). You can do it with mission planner software in config menu->full parameter list.( For information 400Hz is the frequency used in copter firmware.)
With this, the rover should move as expected, without changing the rest of the code or the hardware.
Remember to test everything in a controlled environment and ensure that you have emergency stop capabilities to prevent any accidents. I hope this helps and that you can get your rover going without much trouble!
Good luck with your project!