mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Motors: Updated Motor example.
This commit is contained in:
parent
8a15c69aff
commit
aa6f66f29b
@ -29,6 +29,7 @@
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||
#include <AP_Scheduler/AP_Scheduler.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <SRV_Channel/SRV_Channel.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
@ -43,8 +44,7 @@ void update_motors();
|
||||
#define HELI_TEST 0 // set to 1 to test helicopters
|
||||
#define NUM_OUTPUTS 4 // set to 6 for hexacopter, 8 for octacopter and heli
|
||||
|
||||
RC_Channel rc1(0), rc2(1), rc3(2), rc4(3);
|
||||
RC_Channel rc7(6), rsc(8), h1(0), h2(1), h3(2), h4(3);
|
||||
SRV_Channels srvs;
|
||||
|
||||
// uncomment the row below depending upon what frame you are using
|
||||
//AP_MotorsTri motors(400);
|
||||
@ -68,14 +68,14 @@ void setup()
|
||||
motors.output_min();
|
||||
|
||||
// setup radio
|
||||
rc3.set_radio_min(1000);
|
||||
rc3.set_radio_max(2000);
|
||||
SRV_Channels::srv_channel(2)->set_output_min(1000);
|
||||
SRV_Channels::srv_channel(2)->set_output_max(2000);
|
||||
|
||||
// set rc channel ranges
|
||||
rc1.set_angle(4500);
|
||||
rc2.set_angle(4500);
|
||||
rc3.set_range(1000);
|
||||
rc4.set_angle(4500);
|
||||
SRV_Channels::srv_channel(0)->set_angle(4500);
|
||||
SRV_Channels::srv_channel(1)->set_angle(4500);
|
||||
SRV_Channels::srv_channel(2)->set_range(1000);
|
||||
SRV_Channels::srv_channel(3)->set_angle(4500);
|
||||
|
||||
hal.scheduler->delay(1000);
|
||||
}
|
||||
@ -133,7 +133,7 @@ void stability_test()
|
||||
int16_t rpy_tests[] = {0, 1000, 2000, 3000, 4500, -1000, -2000, -3000, -4500};
|
||||
uint8_t rpy_tests_num = sizeof(rpy_tests) / sizeof(int16_t);
|
||||
|
||||
hal.console->printf("\nTesting stability patch\nThrottle Min:%d Max:%d\n",(int)rc3.get_radio_min(),(int)rc3.get_radio_max());
|
||||
hal.console->printf("\nTesting stability patch\nThrottle Min:%d Max:%d\n",(int)SRV_Channels::srv_channel(2)->get_output_min(),(int)SRV_Channels::srv_channel(2)->get_output_max());
|
||||
|
||||
// arm motors
|
||||
motors.armed(true);
|
||||
@ -211,7 +211,7 @@ void stability_test()
|
||||
void update_motors()
|
||||
{
|
||||
// call update motors 1000 times to get any ramp limiting complete
|
||||
for (uint16_t i=0; i<4000; i++) {
|
||||
for (uint16_t i=0; i<1000; i++) {
|
||||
motors.output();
|
||||
}
|
||||
}
|
||||
|
@ -2,9 +2,6 @@
|
||||
# encoding: utf-8
|
||||
|
||||
def build(bld):
|
||||
# TODO: Test code doesn't build. Fix or delete the test.
|
||||
return
|
||||
|
||||
bld.ap_example(
|
||||
use='ap',
|
||||
)
|
||||
|
Loading…
Reference in New Issue
Block a user