void apmotors_output_set(const struct controloutput *ctl,
                         const struct flightmode *fm) {

    if (motors.armed() && !(fm->armed)) {
        motors.armed(false);
    } else if (!motors.armed() && (fm->armed)) {
        motors.armed(true);
    }

    s_roll.servo_out     = angular_scale(ctl->roll);
    s_pitch.servo_out    = angular_scale(ctl->pitch);
    s_yaw.servo_out      = angular_scale(ctl->yaw);
    s_throttle.servo_out = throttle_scale(ctl->throttle);
    motors.output();
}
예제 #2
0
// stability_test
void motor_order_test()
{
    hal.console->println("testing motor order");
    motors.armed(true);
    for (int8_t i=1; i <= AP_MOTORS_MAX_NUM_MOTORS; i++) {
        hal.console->printf("Motor %d\n",(int)i);
        motors.output_test(i, 1150);
        hal.scheduler->delay(300);
        motors.output_test(i, 1000);
        hal.scheduler->delay(2000);
    }
    motors.armed(false);
    hal.console->println("finished test.");

}
예제 #3
0
// stability_test
void motor_order_test()
{

    motors.armed(true);
    for (int8_t i=1; i <= 4; i++) {
		hal.console->printf("Motor %d\n",(int)i);
        int elapsed =0,stop;
		int start = hal.scheduler->micros();                                                   //Time Test
        motors.output_test(i, 1150);
        stop = hal.scheduler->micros();
        elapsed = stop - start;
        hal.console->printf("  Elapsed Time: %dus\n",elapsed);
        hal.scheduler->delay(300);
        motors.output_test(i, 1000);
        hal.scheduler->delay(2000);
    }
    motors.armed(false);
   
   hal.console->printf("\n\n");
}
예제 #4
0
// stability_test
void stability_test()
{
    int16_t roll_in, pitch_in, yaw_in, throttle_in, avg_out;

    int16_t testing_array[][4] = {
        //  roll,   pitch,  yaw,    throttle
        {   0,      0,      0,      0},
        {   0,      0,      0,      100},
        {   0,      0,      0,      200},
        {   0,      0,      0,      300},
        {   4500,   0,      0,      300},
        {   -4500,  0,      0,      300},
        {   0,   4500,      0,      300},
        {   0,  -4500,      0,      300},
        {   0,      0,   4500,      300},
        {   0,      0,  -4500,      300},
        {   0,      0,      0,      400},
        {   0,      0,      0,      500},
        {   0,      0,      0,      600},
        {   0,      0,      0,      700},
        {   0,      0,      0,      800},
        {   0,      0,      0,      900},
        {   0,      0,      0,      1000},
        {   4500,   0,      0,      1000},
        {   -4500,  0,      0,      1000},
        {   0,   4500,      0,      1000},
        {   0,  -4500,      0,      1000},
        {   0,      0,   4500,      1000},
        {   0,      0,  -4500,      1000},
        {5000,   1000,      0,      1000},
        {5000,   2000,      0,      1000},
        {5000,   3000,      0,      1000},
        {5000,   4000,      0,      1000},
        {5000,   5000,      0,      1000},
        {5000,      0,   1000,      1000},
        {5000,      0,   2000,      1000},
        {5000,      0,   3000,      1000},
        {5000,      0,   4500,      1000}
    };
    uint32_t testing_array_rows = 32;

    hal.console->printf("\nTesting stability patch\nThrottle Min:%d Max:%d\n",(int)rc3.radio_min,(int)rc3.radio_max);

    // arm motors
    motors.armed(true);
    motors.set_interlock(true);
    motors.set_stabilizing(true);

    // run stability test
    for (uint16_t i=0; i<testing_array_rows; i++) {
        roll_in = testing_array[i][0];
        pitch_in = testing_array[i][1];
        yaw_in = testing_array[i][2];
        throttle_in = testing_array[i][3];
        motors.set_pitch(roll_in);
        motors.set_roll(pitch_in);
        motors.set_yaw(yaw_in);
        motors.set_throttle(throttle_in);
        update_motors();
        // calc average output
        avg_out = ((hal.rcout->read(0) + hal.rcout->read(1) + hal.rcout->read(2) + hal.rcout->read(3))/4);

        // display input and output
        hal.console->printf("R:%5d \tP:%5d \tY:%5d \tT:%5d\tMOT1:%5d \tMOT2:%5d \tMOT3:%5d \tMOT4:%5d \t AvgOut:%5d\n",
                (int)roll_in,
                (int)pitch_in,
                (int)yaw_in,
                (int)throttle_in,
                (int)hal.rcout->read(0),
                (int)hal.rcout->read(1),
                (int)hal.rcout->read(2),
                (int)hal.rcout->read(3),
                (int)avg_out);
    }
    // set all inputs to motor library to zero and disarm motors
    motors.set_pitch(0);
    motors.set_roll(0);
    motors.set_yaw(0);
    motors.set_throttle(0);
    motors.armed(false);

    hal.console->println("finished test.");
}