mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.pde
This commit is contained in:
parent
087b2f99c7
commit
2712e5357d
|
@ -1,7 +1,7 @@
|
||||||
/*
|
/*
|
||||||
Example of AP_Motors library.
|
* Example of AP_Motors library.
|
||||||
Code by Randy Mackay. DIYDrones.com
|
* Code by Randy Mackay. DIYDrones.com
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// AVR runtime
|
// AVR runtime
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
|
@ -46,7 +46,7 @@ RC_Channel rc1, rc2, rc3, rc4;
|
||||||
|
|
||||||
// uncomment the row below depending upon what frame you are using
|
// uncomment the row below depending upon what frame you are using
|
||||||
//AP_MotorsTri motors(AP_MOTORS_APM1, &APM_RC, &rc1, &rc2, &rc3, &rc4);
|
//AP_MotorsTri motors(AP_MOTORS_APM1, &APM_RC, &rc1, &rc2, &rc3, &rc4);
|
||||||
AP_MotorsQuad motors(AP_MOTORS_APM2, &APM_RC, &rc1, &rc2, &rc3, &rc4);
|
AP_MotorsQuad motors(AP_MOTORS_APM2, &APM_RC, &rc1, &rc2, &rc3, &rc4);
|
||||||
//AP_MotorsHexa motors(AP_MOTORS_APM1, &APM_RC, &rc1, &rc2, &rc3, &rc4);
|
//AP_MotorsHexa motors(AP_MOTORS_APM1, &APM_RC, &rc1, &rc2, &rc3, &rc4);
|
||||||
//AP_MotorsY6 motors(AP_MOTORS_APM1, &APM_RC, &rc1, &rc2, &rc3, &rc4);
|
//AP_MotorsY6 motors(AP_MOTORS_APM1, &APM_RC, &rc1, &rc2, &rc3, &rc4);
|
||||||
//AP_MotorsOcta motors(AP_MOTORS_APM1, &APM_RC, &rc1, &rc2, &rc3, &rc4);
|
//AP_MotorsOcta motors(AP_MOTORS_APM1, &APM_RC, &rc1, &rc2, &rc3, &rc4);
|
||||||
|
@ -56,59 +56,59 @@ AP_MotorsQuad motors(AP_MOTORS_APM2, &APM_RC, &rc1, &rc2, &rc3, &rc4);
|
||||||
|
|
||||||
// setup
|
// setup
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
Serial.println("AP_Motors library test ver 1.0");
|
Serial.println("AP_Motors library test ver 1.0");
|
||||||
|
|
||||||
RC_Channel::set_apm_rc(&APM_RC);
|
RC_Channel::set_apm_rc(&APM_RC);
|
||||||
APM_RC.Init( &isr_registry ); // APM Radio initialization
|
APM_RC.Init( &isr_registry ); // APM Radio initialization
|
||||||
|
|
||||||
// motor initialisation
|
// motor initialisation
|
||||||
motors.set_update_rate(490);
|
motors.set_update_rate(490);
|
||||||
motors.set_frame_orientation(AP_MOTORS_X_FRAME);
|
motors.set_frame_orientation(AP_MOTORS_X_FRAME);
|
||||||
motors.set_min_throttle(130);
|
motors.set_min_throttle(130);
|
||||||
motors.set_max_throttle(850);
|
motors.set_max_throttle(850);
|
||||||
motors.Init(); // initialise motors
|
motors.Init(); // initialise motors
|
||||||
|
|
||||||
motors.enable();
|
motors.enable();
|
||||||
motors.output_min();
|
motors.output_min();
|
||||||
|
|
||||||
delay(1000);
|
delay(1000);
|
||||||
}
|
}
|
||||||
|
|
||||||
// loop
|
// loop
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
int value;
|
int value;
|
||||||
|
|
||||||
// display help
|
// display help
|
||||||
Serial.println("Press 't' to test motors. Becareful they will spin!");
|
Serial.println("Press 't' to test motors. Becareful they will spin!");
|
||||||
|
|
||||||
// wait for user to enter something
|
// wait for user to enter something
|
||||||
while( !Serial.available() ) {
|
while( !Serial.available() ) {
|
||||||
delay(20);
|
delay(20);
|
||||||
}
|
}
|
||||||
|
|
||||||
// get character from user
|
|
||||||
value = Serial.read();
|
|
||||||
|
|
||||||
// test motors
|
// get character from user
|
||||||
if( value == 't' || value == 'T' ) {
|
value = Serial.read();
|
||||||
Serial.println("testing motors...");
|
|
||||||
motors.armed(true);
|
// test motors
|
||||||
motors.output_test();
|
if( value == 't' || value == 'T' ) {
|
||||||
motors.armed(false);
|
Serial.println("testing motors...");
|
||||||
Serial.println("finished test.");
|
motors.armed(true);
|
||||||
}
|
motors.output_test();
|
||||||
|
motors.armed(false);
|
||||||
|
Serial.println("finished test.");
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// print motor output
|
// print motor output
|
||||||
void print_motor_output()
|
void print_motor_output()
|
||||||
{
|
{
|
||||||
int8_t i;
|
int8_t i;
|
||||||
for(i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
for(i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||||
if( motors.motor_enabled[i] ) {
|
if( motors.motor_enabled[i] ) {
|
||||||
Serial.printf("\t%d %d",i,motors.motor_out[i]);
|
Serial.printf("\t%d %d",i,motors.motor_out[i]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
Loading…
Reference in New Issue