int test_mixer(int argc, char *argv[]) { warnx("testing mixer"); char *filename = "/etc/mixers/IO_pass.mix"; if (argc > 1) filename = argv[1]; warnx("loading: %s", filename); char buf[2048]; load_mixer_file(filename, &buf[0], sizeof(buf)); unsigned loaded = strlen(buf); warnx("loaded: \n\"%s\"\n (%d chars)", &buf[0], loaded); /* load the mixer in chunks, like * in the case of a remote load, * e.g. on PX4IO. */ unsigned nused = 0; const unsigned chunk_size = 64; MixerGroup mixer_group(mixer_callback, 0); /* load at once test */ unsigned xx = loaded; mixer_group.load_from_buf(&buf[0], xx); warnx("complete buffer load: loaded %u mixers", mixer_group.count()); if (mixer_group.count() != 8) return 1; unsigned empty_load = 2; char empty_buf[2]; empty_buf[0] = ' '; empty_buf[1] = '\0'; mixer_group.reset(); mixer_group.load_from_buf(&empty_buf[0], empty_load); warnx("empty buffer load: loaded %u mixers, used: %u", mixer_group.count(), empty_load); if (empty_load != 0) return 1; /* FIRST mark the mixer as invalid */ bool mixer_ok = false; /* THEN actually delete it */ mixer_group.reset(); char mixer_text[256]; /* large enough for one mixer */ unsigned mixer_text_length = 0; unsigned transmitted = 0; warnx("transmitted: %d, loaded: %d", transmitted, loaded); while (transmitted < loaded) { unsigned text_length = (loaded - transmitted > chunk_size) ? chunk_size : loaded - transmitted; /* check for overflow - this would be really fatal */ if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) { bool mixer_ok = false; return 1; } /* append mixer text and nul-terminate */ memcpy(&mixer_text[mixer_text_length], &buf[transmitted], text_length); mixer_text_length += text_length; mixer_text[mixer_text_length] = '\0'; warnx("buflen %u, text:\n\"%s\"", mixer_text_length, &mixer_text[0]); /* process the text buffer, adding new mixers as their descriptions can be parsed */ unsigned resid = mixer_text_length; mixer_group.load_from_buf(&mixer_text[0], resid); /* if anything was parsed */ if (resid != mixer_text_length) { /* only set mixer ok if no residual is left over */ if (resid == 0) { mixer_ok = true; } else { /* not yet reached the end of the mixer, set as not ok */ mixer_ok = false; } warnx("used %u", mixer_text_length - resid); /* copy any leftover text to the base of the buffer for re-use */ if (resid > 0) memcpy(&mixer_text[0], &mixer_text[mixer_text_length - resid], resid); mixer_text_length = resid; } transmitted += text_length; } warnx("chunked load: loaded %u mixers", mixer_group.count()); if (mixer_group.count() != 8) return 1; /* execute the mixer */ float outputs[output_max]; unsigned mixed; const int jmax = 5; pwm_limit_init(&pwm_limit); should_arm = true; /* run through arming phase */ for (int i = 0; i < output_max; i++) { actuator_controls[i] = 0.1f; r_page_servo_disarmed[i] = PWM_LOWEST_MIN; r_page_servo_control_min[i] = PWM_DEFAULT_MIN; r_page_servo_control_max[i] = PWM_DEFAULT_MAX; } warnx("ARMING TEST: STARTING RAMP"); unsigned sleep_quantum_us = 10000; hrt_abstime starttime = hrt_absolute_time(); unsigned sleepcount = 0; while (hrt_elapsed_time(&starttime) < INIT_TIME_US + RAMP_TIME_US) { /* mix */ mixed = mixer_group.mix(&outputs[0], output_max); pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (int i = 0; i < mixed; i++) { /* check mixed outputs to be zero during init phase */ if (hrt_elapsed_time(&starttime) < INIT_TIME_US && r_page_servos[i] != r_page_servo_disarmed[i]) { warnx("disarmed servo value mismatch"); return 1; } if (hrt_elapsed_time(&starttime) >= INIT_TIME_US && r_page_servos[i] + 1 <= r_page_servo_disarmed[i]) { warnx("ramp servo value mismatch"); return 1; } //printf("\t %d: %8.4f limited: %8.4f, servo: %d\n", i, outputs_unlimited[i], outputs[i], (int)r_page_servos[i]); } usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { printf("."); fflush(stdout); } } printf("\n"); warnx("ARMING TEST: NORMAL OPERATION"); for (int j = -jmax; j <= jmax; j++) { for (int i = 0; i < output_max; i++) { actuator_controls[i] = j/10.0f + 0.1f * i; r_page_servo_disarmed[i] = PWM_LOWEST_MIN; r_page_servo_control_min[i] = PWM_DEFAULT_MIN; r_page_servo_control_max[i] = PWM_DEFAULT_MAX; } /* mix */ mixed = mixer_group.mix(&outputs[0], output_max); pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); warnx("mixed %d outputs (max %d)", mixed, output_max); for (int i = 0; i < mixed; i++) { servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f; if (fabsf(servo_predicted[i] - r_page_servos[i]) > 2) { printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, outputs[i], servo_predicted[i], (int)r_page_servos[i]); warnx("mixer violated predicted value"); return 1; } } } warnx("ARMING TEST: DISARMING"); starttime = hrt_absolute_time(); sleepcount = 0; should_arm = false; while (hrt_elapsed_time(&starttime) < 600000) { /* mix */ mixed = mixer_group.mix(&outputs[0], output_max); pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (int i = 0; i < mixed; i++) { /* check mixed outputs to be zero during init phase */ if (r_page_servos[i] != r_page_servo_disarmed[i]) { warnx("disarmed servo value mismatch"); return 1; } //printf("\t %d: %8.4f limited: %8.4f, servo: %d\n", i, outputs_unlimited[i], outputs[i], (int)r_page_servos[i]); } usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { printf("."); fflush(stdout); } } printf("\n"); warnx("ARMING TEST: REARMING: STARTING RAMP"); starttime = hrt_absolute_time(); sleepcount = 0; should_arm = true; while (hrt_elapsed_time(&starttime) < 600000 + RAMP_TIME_US) { /* mix */ mixed = mixer_group.mix(&outputs[0], output_max); pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (int i = 0; i < mixed; i++) { /* predict value */ servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f; /* check ramp */ if (hrt_elapsed_time(&starttime) < RAMP_TIME_US && (r_page_servos[i] + 1 <= r_page_servo_disarmed[i] || r_page_servos[i] > servo_predicted[i])) { warnx("ramp servo value mismatch"); return 1; } /* check post ramp phase */ if (hrt_elapsed_time(&starttime) > RAMP_TIME_US && fabsf(servo_predicted[i] - r_page_servos[i]) > 2) { printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, outputs[i], servo_predicted[i], (int)r_page_servos[i]); warnx("mixer violated predicted value"); return 1; } //printf("\t %d: %8.4f limited: %8.4f, servo: %d\n", i, outputs_unlimited[i], outputs[i], (int)r_page_servos[i]); } usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { printf("."); fflush(stdout); } } printf("\n"); /* load multirotor at once test */ mixer_group.reset(); if (argc > 2) filename = argv[2]; else filename = "/etc/mixers/FMU_quad_w.mix"; load_mixer_file(filename, &buf[0], sizeof(buf)); loaded = strlen(buf); warnx("loaded: \n\"%s\"\n (%d chars)", &buf[0], loaded); unsigned mc_loaded = loaded; mixer_group.load_from_buf(&buf[0], mc_loaded); warnx("complete buffer load: loaded %u mixers", mixer_group.count()); if (mixer_group.count() != 5) { warnx("FAIL: Quad W mixer load failed"); return 1; } warnx("SUCCESS: No errors in mixer test"); }
int user_start(int argc, char *argv[]) { /* run C++ ctors before we go any further */ up_cxxinitialize(); /* reset all to zero */ memset(&system_state, 0, sizeof(system_state)); /* configure the high-resolution time/callout interface */ hrt_init(); /* calculate our fw CRC so FMU can decide if we need to update */ calculate_fw_crc(); /* * Poll at 1ms intervals for received bytes that have not triggered * a DMA event. */ #ifdef CONFIG_ARCH_DMA hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); #endif /* print some startup info */ lowsyslog("\nPX4IO: starting\n"); /* default all the LEDs to off while we start */ LED_AMBER(false); LED_BLUE(false); LED_SAFETY(false); #ifdef GPIO_LED4 LED_RING(false); #endif /* turn on servo power (if supported) */ #ifdef POWER_SERVO POWER_SERVO(true); #endif /* turn off S.Bus out (if supported) */ #ifdef ENABLE_SBUS_OUT ENABLE_SBUS_OUT(false); #endif /* start the safety switch handler */ safety_init(); /* configure the first 8 PWM outputs (i.e. all of them) */ up_pwm_servo_init(0xff); /* initialise the control inputs */ controls_init(); /* set up the ADC */ adc_init(); /* start the FMU interface */ interface_init(); /* add a performance counter for mixing */ perf_counter_t mixer_perf = perf_alloc(PC_ELAPSED, "mix"); /* add a performance counter for controls */ perf_counter_t controls_perf = perf_alloc(PC_ELAPSED, "controls"); /* and one for measuring the loop rate */ perf_counter_t loop_perf = perf_alloc(PC_INTERVAL, "loop"); struct mallinfo minfo = mallinfo(); lowsyslog("MEM: free %u, largest %u\n", minfo.mxordblk, minfo.fordblks); /* initialize PWM limit lib */ pwm_limit_init(&pwm_limit); /* * P O L I C E L I G H T S * * Not enough memory, lock down. * * We might need to allocate mixers later, and this will * ensure that a developer doing a change will notice * that he just burned the remaining RAM with static * allocations. We don't want him to be able to * get past that point. This needs to be clearly * documented in the dev guide. * */ if (minfo.mxordblk < 600) { lowsyslog("ERR: not enough MEM"); bool phase = false; while (true) { if (phase) { LED_AMBER(true); LED_BLUE(false); } else { LED_AMBER(false); LED_BLUE(true); } up_udelay(250000); phase = !phase; } } /* Start the failsafe led init */ failsafe_led_init(); /* * Run everything in a tight loop. */ uint64_t last_debug_time = 0; uint64_t last_heartbeat_time = 0; for (;;) { /* track the rate at which the loop is running */ perf_count(loop_perf); /* kick the mixer */ perf_begin(mixer_perf); mixer_tick(); perf_end(mixer_perf); /* kick the control inputs */ perf_begin(controls_perf); controls_tick(); perf_end(controls_perf); if ((hrt_absolute_time() - last_heartbeat_time) > 250 * 1000) { last_heartbeat_time = hrt_absolute_time(); heartbeat_blink(); } ring_blink(); check_reboot(); /* check for debug activity (default: none) */ show_debug_messages(); /* post debug state at ~1Hz - this is via an auxiliary serial port * DEFAULTS TO OFF! */ if (hrt_absolute_time() - last_debug_time > (1000 * 1000)) { isr_debug(1, "d:%u s=0x%x a=0x%x f=0x%x m=%u", (unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG], (unsigned)r_status_flags, (unsigned)r_setup_arming, (unsigned)r_setup_features, (unsigned)mallinfo().mxordblk); last_debug_time = hrt_absolute_time(); } } }
/** * Main loop function */ void PCA9685::i2cpwm() { if (_mode == IOX_MODE_TEST_OUT) { setPin(0, PCA9685_PWMCENTER); _should_run = true; } else if (_mode == IOX_MODE_OFF) { _should_run = false; } else { if (!_mode_on_initialized) { // Init PWM limits pwm_limit_init(&_pwm_limit); // Get arming state _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); /* Subscribe to actuator groups */ subscribe(); /* set the uorb update interval lower than the driver pwm interval */ for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; ++i) { orb_set_interval(_control_subs[i], 1000.0f / PCA9685_PWMFREQ - 5); } _mode_on_initialized = true; } /* check if anything updated */ int ret = ::poll(_poll_fds, _poll_fds_num, 0); if (ret < 0) { DEVICE_LOG("poll error %d", errno); } else if (ret == 0) { // warnx("no PWM: failsafe"); } else { /* get controls for required topics */ unsigned poll_id = 0; for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { if (_poll_fds[poll_id].revents & POLLIN) { orb_copy(_control_topics[i], _control_subs[i], &_controls[i]); } } poll_id++; } if (_mixers != nullptr) { size_t num_outputs = actuator_outputs_s::NUM_ACTUATOR_OUTPUTS; // do mixing num_outputs = _mixers->mix(_outputs, num_outputs, NULL); // disable unused ports by setting their output to NaN for (size_t i = 0; i < sizeof(_outputs) / sizeof(_outputs[0]); i++) { if (i >= num_outputs) { _outputs[i] = NAN_VALUE; } } // Finally, write servo values to motors for (int i = 0; i < num_outputs; i++) { uint16_t new_value = PCA9685_PWMCENTER + (_outputs[i] * M_PI_F * PCA9685_SCALE); // DEVICE_DEBUG("%d: current: %u, new %u, control %.2f", i, _current_values[i], new_value, // (double)_controls[1].control[i]); if (isfinite(new_value) && new_value >= PCA9685_PWMMIN && new_value <= PCA9685_PWMMAX) { setPin(i, new_value); _rates[i] = new_value; } } } } bool updated; // Update Arming state orb_check(_armed_sub, &updated); if (updated) { orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed); bool set_armed = (_armed.armed || _armed.prearmed) && !_armed.lockdown; if (_servo_armed != set_armed) { _servo_armed = set_armed; } } // Update AUX controls update // orb_check(_actuator_controls_sub, &updated); // if (updated) { // size_t num_outputs = actuator_outputs_s::NUM_ACTUATOR_OUTPUTS; // // // Get updated actuator // // Only update actuator 1 for now // orb_copy(ORB_ID(actuator_controls_1), _actuator_controls_sub, &_controls[1]); // // // } _should_run = true; } // check if any activity remains, else stop if (!_should_run) { _running = false; return; } // re-queue ourselves to run again later _running = true; work_queue(LPWORK, &_work, (worker_t)&PCA9685::i2cpwm_trampoline, this, _i2cpwm_interval); }
void PX4FMU::task_main() { /* force a reset of the update rate */ _current_update_rate = 0; _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); _param_sub = orb_subscribe(ORB_ID(parameter_update)); /* advertise the mixed control outputs */ actuator_outputs_s outputs; memset(&outputs, 0, sizeof(outputs)); #ifdef HRT_PPM_CHANNEL // rc input, published to ORB struct rc_input_values rc_in; orb_advert_t to_input_rc = 0; memset(&rc_in, 0, sizeof(rc_in)); rc_in.input_source = RC_INPUT_SOURCE_PX4FMU_PPM; #endif /* initialize PWM limit lib */ pwm_limit_init(&_pwm_limit); update_pwm_rev_mask(); /* loop until killed */ while (!_task_should_exit) { if (_groups_subscribed != _groups_required) { subscribe(); _groups_subscribed = _groups_required; /* force setting update rate */ _current_update_rate = 0; } /* * Adjust actuator topic update rate to keep up with * the highest servo update rate configured. * * We always mix at max rate; some channels may update slower. */ unsigned max_rate = (_pwm_default_rate > _pwm_alt_rate) ? _pwm_default_rate : _pwm_alt_rate; if (_current_update_rate != max_rate) { _current_update_rate = max_rate; int update_rate_in_ms = int(1000 / _current_update_rate); /* reject faster than 500 Hz updates */ if (update_rate_in_ms < 2) { update_rate_in_ms = 2; } /* reject slower than 10 Hz updates */ if (update_rate_in_ms > 100) { update_rate_in_ms = 100; } debug("adjusted actuator update interval to %ums", update_rate_in_ms); for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { orb_set_interval(_control_subs[i], update_rate_in_ms); } } // set to current max rate, even if we are actually checking slower/faster _current_update_rate = max_rate; } /* sleep waiting for data, stopping to check for PPM * input at 50Hz */ int ret = ::poll(_poll_fds, _poll_fds_num, CONTROL_INPUT_DROP_LIMIT_MS); /* this would be bad... */ if (ret < 0) { log("poll error %d", errno); continue; } else if (ret == 0) { /* timeout: no control data, switch to failsafe values */ // warnx("no PWM: failsafe"); } else { /* get controls for required topics */ unsigned poll_id = 0; for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { if (_poll_fds[poll_id].revents & POLLIN) { orb_copy(_control_topics[i], _control_subs[i], &_controls[i]); } poll_id++; } } /* can we mix? */ if (_mixers != nullptr) { unsigned num_outputs; switch (_mode) { case MODE_2PWM: num_outputs = 2; break; case MODE_4PWM: num_outputs = 4; break; case MODE_6PWM: num_outputs = 6; break; case MODE_8PWM: num_outputs = 8; break; default: num_outputs = 0; break; } /* do mixing */ outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs, NULL); outputs.timestamp = hrt_absolute_time(); /* iterate actuators */ for (unsigned i = 0; i < num_outputs; i++) { /* last resort: catch NaN and INF */ if ((i >= outputs.noutputs) || !isfinite(outputs.output[i])) { /* * Value is NaN, INF or out of band - set to the minimum value. * This will be clearly visible on the servo status and will limit the risk of accidentally * spinning motors. It would be deadly in flight. */ outputs.output[i] = -1.0f; } } uint16_t pwm_limited[num_outputs]; /* the PWM limit call takes care of out of band errors and constrains */ pwm_limit_calc(_servo_armed, num_outputs, _reverse_pwm_mask, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit); /* output to the servos */ for (unsigned i = 0; i < num_outputs; i++) { up_pwm_servo_set(i, pwm_limited[i]); } /* publish mixed control outputs */ if (_outputs_pub != nullptr) { _outputs_pub = orb_advertise_multi(ORB_ID(actuator_outputs), &outputs, &_actuator_output_topic_instance, ORB_PRIO_DEFAULT); } else { orb_publish(ORB_ID(actuator_outputs), _outputs_pub, &outputs); } } } /* check arming state */ bool updated = false; orb_check(_armed_sub, &updated); if (updated) { orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed); /* update the armed status and check that we're not locked down */ bool set_armed = _armed.armed && !_armed.lockdown; if (_servo_armed != set_armed) _servo_armed = set_armed; /* update PWM status if armed or if disarmed PWM values are set */ bool pwm_on = (_armed.armed || _num_disarmed_set > 0); if (_pwm_on != pwm_on) { _pwm_on = pwm_on; up_pwm_servo_arm(pwm_on); } } orb_check(_param_sub, &updated); if (updated) { parameter_update_s pupdate; orb_copy(ORB_ID(parameter_update), _param_sub, &pupdate); update_pwm_rev_mask(); } #ifdef HRT_PPM_CHANNEL // see if we have new PPM input data if (ppm_last_valid_decode != rc_in.timestamp_last_signal) { // we have a new PPM frame. Publish it. rc_in.channel_count = ppm_decoded_channels; if (rc_in.channel_count > RC_INPUT_MAX_CHANNELS) { rc_in.channel_count = RC_INPUT_MAX_CHANNELS; } for (uint8_t i = 0; i < rc_in.channel_count; i++) { rc_in.values[i] = ppm_buffer[i]; } rc_in.timestamp_publication = ppm_last_valid_decode; rc_in.timestamp_last_signal = ppm_last_valid_decode; rc_in.rc_ppm_frame_length = ppm_frame_length; rc_in.rssi = RC_INPUT_RSSI_MAX; rc_in.rc_failsafe = false; rc_in.rc_lost = false; rc_in.rc_lost_frame_count = 0; rc_in.rc_total_frame_count = 0; /* lazily advertise on first publication */ if (to_input_rc == 0) { to_input_rc = orb_advertise(ORB_ID(input_rc), &rc_in); } else { orb_publish(ORB_ID(input_rc), to_input_rc, &rc_in); } } #endif } for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { ::close(_control_subs[i]); _control_subs[i] = -1; } } ::close(_armed_sub); ::close(_param_sub); /* make sure servos are off */ up_pwm_servo_deinit(); log("stopping"); /* note - someone else is responsible for restoring the GPIO config */ /* tell the dtor that we are exiting */ _task = -1; _exit(0); }
void task_main(int argc, char *argv[]) { _is_running = true; if (uart_initialize(_device) < 0) { PX4_ERR("Failed to initialize UART."); return; } // Subscribe for orb topics _controls_sub = orb_subscribe(ORB_ID(actuator_controls_0)); _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); // Start disarmed _armed.armed = false; _armed.prearmed = false; // Set up poll topic px4_pollfd_struct_t fds[1]; fds[0].fd = _controls_sub; fds[0].events = POLLIN; /* Don't limit poll intervall for now, 250 Hz should be fine. */ //orb_set_interval(_controls_sub, 10); // Set up mixer if (initialize_mixer(MIXER_FILENAME) < 0) { PX4_ERR("Mixer initialization failed."); return; } pwm_limit_init(&_pwm_limit); // TODO XXX: this is needed otherwise we crash in the callback context. _rc_pub = orb_advertise(ORB_ID(input_rc), &_rc); // Main loop while (!_task_should_exit) { int pret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 10); /* Timed out, do a periodic check for _task_should_exit. */ if (pret == 0) { continue; } /* This is undesirable but not much we can do. */ if (pret < 0) { PX4_WARN("poll error %d, %d", pret, errno); /* sleep a bit before next try */ usleep(100000); continue; } if (fds[0].revents & POLLIN) { orb_copy(ORB_ID(actuator_controls_0), _controls_sub, &_controls); _outputs.timestamp = _controls.timestamp; /* do mixing */ _outputs.noutputs = _mixer->mix(_outputs.output, 0 /* not used */, NULL); /* disable unused ports by setting their output to NaN */ for (size_t i = _outputs.noutputs; i < sizeof(_outputs.output) / sizeof(_outputs.output[0]); i++) { _outputs.output[i] = NAN; } const uint16_t reverse_mask = 0; // TODO FIXME: these should probably be params const uint16_t disarmed_pwm[4] = {900, 900, 900, 900}; const uint16_t min_pwm[4] = {1230, 1230, 1230, 1230}; const uint16_t max_pwm[4] = {1900, 1900, 1900, 1900}; uint16_t pwm[4]; // TODO FIXME: pre-armed seems broken pwm_limit_calc(_armed.armed, false/*_armed.prearmed*/, _outputs.noutputs, reverse_mask, disarmed_pwm, min_pwm, max_pwm, _outputs.output, pwm, &_pwm_limit); send_outputs_mavlink(pwm, 4); if (_outputs_pub != nullptr) { orb_publish(ORB_ID(actuator_outputs), _outputs_pub, &_outputs); } else { _outputs_pub = orb_advertise(ORB_ID(actuator_outputs), &_outputs); } } bool updated; orb_check(_armed_sub, &updated); if (updated) { orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed); } } uart_deinitialize(); orb_unsubscribe(_controls_sub); orb_unsubscribe(_armed_sub); _is_running = false; }
int user_start(int argc, char *argv[]) { /* configure the first 8 PWM outputs (i.e. all of them) */ up_pwm_servo_init(0xff); #if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE) /* run C++ ctors before we go any further */ up_cxxinitialize(); # if defined(CONFIG_EXAMPLES_NSH_CXXINITIALIZE) # error CONFIG_EXAMPLES_NSH_CXXINITIALIZE Must not be defined! Use CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE. # endif #else # error platform is dependent on c++ both CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE must be defined. #endif /* reset all to zero */ memset(&system_state, 0, sizeof(system_state)); /* configure the high-resolution time/callout interface */ hrt_init(); /* calculate our fw CRC so FMU can decide if we need to update */ calculate_fw_crc(); /* * Poll at 1ms intervals for received bytes that have not triggered * a DMA event. */ #ifdef CONFIG_ARCH_DMA hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); #endif /* print some startup info */ syslog(LOG_INFO, "\nPX4IO: starting\n"); /* default all the LEDs to off while we start */ LED_AMBER(false); LED_BLUE(false); LED_SAFETY(false); #ifdef GPIO_LED4 LED_RING(false); #endif /* turn on servo power (if supported) */ #ifdef POWER_SERVO POWER_SERVO(true); #endif /* turn off S.Bus out (if supported) */ #ifdef ENABLE_SBUS_OUT ENABLE_SBUS_OUT(false); #endif /* start the safety switch handler */ safety_init(); /* initialise the control inputs */ controls_init(); /* set up the ADC */ adc_init(); /* start the FMU interface */ interface_init(); /* add a performance counter for mixing */ perf_counter_t mixer_perf = perf_alloc(PC_ELAPSED, "mix"); /* add a performance counter for controls */ perf_counter_t controls_perf = perf_alloc(PC_ELAPSED, "controls"); /* and one for measuring the loop rate */ perf_counter_t loop_perf = perf_alloc(PC_INTERVAL, "loop"); struct mallinfo minfo = mallinfo(); r_page_status[PX4IO_P_STATUS_FREEMEM] = minfo.mxordblk; syslog(LOG_INFO, "MEM: free %u, largest %u\n", minfo.mxordblk, minfo.fordblks); /* initialize PWM limit lib */ pwm_limit_init(&pwm_limit); /* * P O L I C E L I G H T S * * Not enough memory, lock down. * * We might need to allocate mixers later, and this will * ensure that a developer doing a change will notice * that he just burned the remaining RAM with static * allocations. We don't want him to be able to * get past that point. This needs to be clearly * documented in the dev guide. * */ if (minfo.mxordblk < 600) { syslog(LOG_ERR, "ERR: not enough MEM"); bool phase = false; while (true) { if (phase) { LED_AMBER(true); LED_BLUE(false); } else { LED_AMBER(false); LED_BLUE(true); } up_udelay(250000); phase = !phase; } } /* Start the failsafe led init */ failsafe_led_init(); /* * Run everything in a tight loop. */ uint64_t last_debug_time = 0; uint64_t last_heartbeat_time = 0; uint64_t last_loop_time = 0; for (;;) { dt = (hrt_absolute_time() - last_loop_time) / 1000000.0f; last_loop_time = hrt_absolute_time(); if (dt < 0.0001f) { dt = 0.0001f; } else if (dt > 0.02f) { dt = 0.02f; } /* track the rate at which the loop is running */ perf_count(loop_perf); /* kick the mixer */ perf_begin(mixer_perf); mixer_tick(); perf_end(mixer_perf); /* kick the control inputs */ perf_begin(controls_perf); controls_tick(); perf_end(controls_perf); /* some boards such as Pixhawk 2.1 made the unfortunate choice to combine the blue led channel with the IMU heater. We need a software hack to fix the hardware hack by allowing to disable the LED / heater. */ if (r_page_setup[PX4IO_P_SETUP_THERMAL] == PX4IO_THERMAL_IGNORE) { /* blink blue LED at 4Hz in normal operation. When in override blink 4x faster so the user can clearly see that override is happening. This helps when pre-flight testing the override system */ uint32_t heartbeat_period_us = 250 * 1000UL; if (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) { heartbeat_period_us /= 4; } if ((hrt_absolute_time() - last_heartbeat_time) > heartbeat_period_us) { last_heartbeat_time = hrt_absolute_time(); heartbeat_blink(); } } else if (r_page_setup[PX4IO_P_SETUP_THERMAL] < PX4IO_THERMAL_FULL) { /* switch resistive heater off */ LED_BLUE(false); } else { /* switch resistive heater hard on */ LED_BLUE(true); } update_mem_usage(); ring_blink(); check_reboot(); /* check for debug activity (default: none) */ show_debug_messages(); /* post debug state at ~1Hz - this is via an auxiliary serial port * DEFAULTS TO OFF! */ if (hrt_absolute_time() - last_debug_time > (1000 * 1000)) { isr_debug(1, "d:%u s=0x%x a=0x%x f=0x%x m=%u", (unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG], (unsigned)r_status_flags, (unsigned)r_setup_arming, (unsigned)r_setup_features, (unsigned)mallinfo().mxordblk); last_debug_time = hrt_absolute_time(); } } }
bool MixerTest::mixerTest() { /* * PWM limit structure */ pwm_limit_t pwm_limit; bool should_arm = false; uint16_t r_page_servo_disarmed[output_max]; uint16_t r_page_servo_control_min[output_max]; uint16_t r_page_servo_control_max[output_max]; uint16_t r_page_servos[output_max]; uint16_t servo_predicted[output_max]; int16_t reverse_pwm_mask = 0; bool load_ok = load_mixer(MIXER_PATH(IO_pass.mix), 8); if (!load_ok) { return load_ok; } /* execute the mixer */ float outputs[output_max]; unsigned mixed; const int jmax = 5; pwm_limit_init(&pwm_limit); /* run through arming phase */ for (unsigned i = 0; i < output_max; i++) { actuator_controls[i] = 0.1f; r_page_servo_disarmed[i] = PWM_MOTOR_OFF; r_page_servo_control_min[i] = PWM_DEFAULT_MIN; r_page_servo_control_max[i] = PWM_DEFAULT_MAX; } //PX4_INFO("PRE-ARM TEST: DISABLING SAFETY"); /* mix */ should_prearm = true; mixed = mixer_group.mix(&outputs[0], output_max, nullptr); pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (unsigned i = 0; i < mixed; i++) { //fprintf(stderr, "pre-arm:\t %d: out: %8.4f, servo: %d \n", i, (double)outputs[i], (int)r_page_servos[i]); if (i != actuator_controls_s::INDEX_THROTTLE) { if (r_page_servos[i] < r_page_servo_control_min[i]) { warnx("active servo < min"); return false; } } else { if (r_page_servos[i] != r_page_servo_disarmed[i]) { warnx("throttle output != 0 (this check assumed the IO pass mixer!)"); return false; } } } should_arm = true; should_prearm = false; /* simulate another orb_copy() from actuator controls */ for (unsigned i = 0; i < output_max; i++) { actuator_controls[i] = 0.1f; } //PX4_INFO("ARMING TEST: STARTING RAMP"); unsigned sleep_quantum_us = 10000; hrt_abstime starttime = hrt_absolute_time(); unsigned sleepcount = 0; while (hrt_elapsed_time(&starttime) < INIT_TIME_US + RAMP_TIME_US + 2 * sleep_quantum_us) { /* mix */ mixed = mixer_group.mix(&outputs[0], output_max, nullptr); pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (unsigned i = 0; i < mixed; i++) { //fprintf(stderr, "ramp:\t %d: out: %8.4f, servo: %d \n", i, (double)outputs[i], (int)r_page_servos[i]); /* check mixed outputs to be zero during init phase */ if (hrt_elapsed_time(&starttime) < INIT_TIME_US && r_page_servos[i] != r_page_servo_disarmed[i]) { PX4_ERR("disarmed servo value mismatch: %d vs %d", r_page_servos[i], r_page_servo_disarmed[i]); return false; } if (hrt_elapsed_time(&starttime) >= INIT_TIME_US && r_page_servos[i] + 1 <= r_page_servo_disarmed[i]) { PX4_ERR("ramp servo value mismatch"); return false; } } usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { fflush(stdout); } } //PX4_INFO("ARMING TEST: NORMAL OPERATION"); for (int j = -jmax; j <= jmax; j++) { for (unsigned i = 0; i < output_max; i++) { actuator_controls[i] = j / 10.0f + 0.1f * i; r_page_servo_disarmed[i] = PWM_LOWEST_MIN; r_page_servo_control_min[i] = PWM_DEFAULT_MIN; r_page_servo_control_max[i] = PWM_DEFAULT_MAX; } /* mix */ mixed = mixer_group.mix(&outputs[0], output_max, nullptr); pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //fprintf(stderr, "mixed %d outputs (max %d)", mixed, output_max); for (unsigned i = 0; i < mixed; i++) { servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f; if (abs(servo_predicted[i] - r_page_servos[i]) > MIXER_DIFFERENCE_THRESHOLD) { fprintf(stderr, "\t %d: %8.4f predicted: %d, servo: %d\n", i, (double)outputs[i], servo_predicted[i], (int)r_page_servos[i]); PX4_ERR("mixer violated predicted value"); return false; } } } //PX4_INFO("ARMING TEST: DISARMING"); starttime = hrt_absolute_time(); sleepcount = 0; should_arm = false; while (hrt_elapsed_time(&starttime) < 600000) { /* mix */ mixed = mixer_group.mix(&outputs[0], output_max, nullptr); pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (unsigned i = 0; i < mixed; i++) { //fprintf(stderr, "disarmed:\t %d: out: %8.4f, servo: %d \n", i, (double)outputs[i], (int)r_page_servos[i]); /* check mixed outputs to be zero during init phase */ if (r_page_servos[i] != r_page_servo_disarmed[i]) { PX4_ERR("disarmed servo value mismatch"); return false; } } usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { //printf("."); //fflush(stdout); } } //printf("\n"); //PX4_INFO("ARMING TEST: REARMING: STARTING RAMP"); starttime = hrt_absolute_time(); sleepcount = 0; should_arm = true; while (hrt_elapsed_time(&starttime) < 600000 + RAMP_TIME_US) { /* mix */ mixed = mixer_group.mix(&outputs[0], output_max, nullptr); pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (unsigned i = 0; i < mixed; i++) { /* predict value */ servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f; /* check ramp */ //fprintf(stderr, "ramp:\t %d: out: %8.4f, servo: %d \n", i, (double)outputs[i], (int)r_page_servos[i]); if (hrt_elapsed_time(&starttime) < RAMP_TIME_US && (r_page_servos[i] + 1 <= r_page_servo_disarmed[i] || r_page_servos[i] > servo_predicted[i])) { PX4_ERR("ramp servo value mismatch"); return false; } /* check post ramp phase */ if (hrt_elapsed_time(&starttime) > RAMP_TIME_US && abs(servo_predicted[i] - r_page_servos[i]) > 2) { printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, (double)outputs[i], servo_predicted[i], (int)r_page_servos[i]); PX4_ERR("mixer violated predicted value"); return false; } } usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { // printf("."); // fflush(stdout); } } return true; }
int test_mixer(int argc, char *argv[]) { /* * PWM limit structure */ pwm_limit_t pwm_limit; bool should_arm = false; uint16_t r_page_servo_disarmed[output_max]; uint16_t r_page_servo_control_min[output_max]; uint16_t r_page_servo_control_max[output_max]; uint16_t r_page_servos[output_max]; uint16_t servo_predicted[output_max]; int16_t reverse_pwm_mask = 0; //PX4_INFO("testing mixer"); #if !defined(CONFIG_ARCH_BOARD_SITL) const char *filename = "/etc/mixers/IO_pass.mix"; #else const char *filename = "ROMFS/px4fmu_test/mixers/IO_pass.mix"; #endif //PX4_INFO("loading: %s", filename); char buf[2048]; load_mixer_file(filename, &buf[0], sizeof(buf)); unsigned loaded = strlen(buf); //fprintf(stderr, "loaded: \n\"%s\"\n (%d chars)", &buf[0], loaded); /* load the mixer in chunks, like * in the case of a remote load, * e.g. on PX4IO. */ const unsigned chunk_size = 64; MixerGroup mixer_group(mixer_callback, 0); /* load at once test */ unsigned xx = loaded; mixer_group.load_from_buf(&buf[0], xx); //ASSERT_EQ(mixer_group.count(), 8); unsigned empty_load = 2; char empty_buf[2]; empty_buf[0] = ' '; empty_buf[1] = '\0'; mixer_group.reset(); mixer_group.load_from_buf(&empty_buf[0], empty_load); //PX4_INFO("empty buffer load: loaded %u mixers, used: %u", mixer_group.count(), empty_load); //ASSERT_NE(empty_load, 0); if (empty_load != 0) { return 1; } /* FIRST mark the mixer as invalid */ /* THEN actually delete it */ mixer_group.reset(); char mixer_text[256]; /* large enough for one mixer */ unsigned mixer_text_length = 0; unsigned transmitted = 0; //PX4_INFO("transmitted: %d, loaded: %d", transmitted, loaded); while (transmitted < loaded) { unsigned text_length = (loaded - transmitted > chunk_size) ? chunk_size : loaded - transmitted; /* check for overflow - this would be really fatal */ if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) { return 1; } /* append mixer text and nul-terminate */ memcpy(&mixer_text[mixer_text_length], &buf[transmitted], text_length); mixer_text_length += text_length; mixer_text[mixer_text_length] = '\0'; //fprintf(stderr, "buflen %u, text:\n\"%s\"", mixer_text_length, &mixer_text[0]); /* process the text buffer, adding new mixers as their descriptions can be parsed */ unsigned resid = mixer_text_length; mixer_group.load_from_buf(&mixer_text[0], resid); /* if anything was parsed */ if (resid != mixer_text_length) { //fprintf(stderr, "used %u", mixer_text_length - resid); /* copy any leftover text to the base of the buffer for re-use */ if (resid > 0) { memcpy(&mixer_text[0], &mixer_text[mixer_text_length - resid], resid); } mixer_text_length = resid; } transmitted += text_length; } //PX4_INFO("chunked load: loaded %u mixers", mixer_group.count()); if (mixer_group.count() != 8) { return 1; } /* execute the mixer */ float outputs[output_max]; unsigned mixed; const int jmax = 5; pwm_limit_init(&pwm_limit); /* run through arming phase */ for (unsigned i = 0; i < output_max; i++) { actuator_controls[i] = 0.1f; r_page_servo_disarmed[i] = PWM_MOTOR_OFF; r_page_servo_control_min[i] = PWM_DEFAULT_MIN; r_page_servo_control_max[i] = PWM_DEFAULT_MAX; } //PX4_INFO("PRE-ARM TEST: DISABLING SAFETY"); /* mix */ should_prearm = true; mixed = mixer_group.mix(&outputs[0], output_max, NULL); pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (unsigned i = 0; i < mixed; i++) { //fprintf(stderr, "pre-arm:\t %d: out: %8.4f, servo: %d \n", i, (double)outputs[i], (int)r_page_servos[i]); if (i != actuator_controls_s::INDEX_THROTTLE) { if (r_page_servos[i] < r_page_servo_control_min[i]) { warnx("active servo < min"); return 1; } } else { if (r_page_servos[i] != r_page_servo_disarmed[i]) { warnx("throttle output != 0 (this check assumed the IO pass mixer!)"); return 1; } } } should_arm = true; should_prearm = false; /* simulate another orb_copy() from actuator controls */ for (unsigned i = 0; i < output_max; i++) { actuator_controls[i] = 0.1f; } //PX4_INFO("ARMING TEST: STARTING RAMP"); unsigned sleep_quantum_us = 10000; hrt_abstime starttime = hrt_absolute_time(); unsigned sleepcount = 0; while (hrt_elapsed_time(&starttime) < INIT_TIME_US + RAMP_TIME_US + 2 * sleep_quantum_us) { /* mix */ mixed = mixer_group.mix(&outputs[0], output_max, NULL); pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (unsigned i = 0; i < mixed; i++) { //fprintf(stderr, "ramp:\t %d: out: %8.4f, servo: %d \n", i, (double)outputs[i], (int)r_page_servos[i]); /* check mixed outputs to be zero during init phase */ if (hrt_elapsed_time(&starttime) < INIT_TIME_US && r_page_servos[i] != r_page_servo_disarmed[i]) { PX4_ERR("disarmed servo value mismatch: %d vs %d", r_page_servos[i], r_page_servo_disarmed[i]); return 1; } if (hrt_elapsed_time(&starttime) >= INIT_TIME_US && r_page_servos[i] + 1 <= r_page_servo_disarmed[i]) { PX4_ERR("ramp servo value mismatch"); return 1; } } usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { fflush(stdout); } } //PX4_INFO("ARMING TEST: NORMAL OPERATION"); for (int j = -jmax; j <= jmax; j++) { for (unsigned i = 0; i < output_max; i++) { actuator_controls[i] = j / 10.0f + 0.1f * i; r_page_servo_disarmed[i] = PWM_LOWEST_MIN; r_page_servo_control_min[i] = PWM_DEFAULT_MIN; r_page_servo_control_max[i] = PWM_DEFAULT_MAX; } /* mix */ mixed = mixer_group.mix(&outputs[0], output_max, NULL); pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //fprintf(stderr, "mixed %d outputs (max %d)", mixed, output_max); for (unsigned i = 0; i < mixed; i++) { servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f; if (abs(servo_predicted[i] - r_page_servos[i]) > MIXER_DIFFERENCE_THRESHOLD) { fprintf(stderr, "\t %d: %8.4f predicted: %d, servo: %d\n", i, (double)outputs[i], servo_predicted[i], (int)r_page_servos[i]); PX4_ERR("mixer violated predicted value"); return 1; } } } //PX4_INFO("ARMING TEST: DISARMING"); starttime = hrt_absolute_time(); sleepcount = 0; should_arm = false; while (hrt_elapsed_time(&starttime) < 600000) { /* mix */ mixed = mixer_group.mix(&outputs[0], output_max, NULL); pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (unsigned i = 0; i < mixed; i++) { //fprintf(stderr, "disarmed:\t %d: out: %8.4f, servo: %d \n", i, (double)outputs[i], (int)r_page_servos[i]); /* check mixed outputs to be zero during init phase */ if (r_page_servos[i] != r_page_servo_disarmed[i]) { PX4_ERR("disarmed servo value mismatch"); return 1; } } usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { //printf("."); //fflush(stdout); } } //printf("\n"); //PX4_INFO("ARMING TEST: REARMING: STARTING RAMP"); starttime = hrt_absolute_time(); sleepcount = 0; should_arm = true; while (hrt_elapsed_time(&starttime) < 600000 + RAMP_TIME_US) { /* mix */ mixed = mixer_group.mix(&outputs[0], output_max, NULL); pwm_limit_calc(should_arm, should_prearm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); for (unsigned i = 0; i < mixed; i++) { /* predict value */ servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f; /* check ramp */ //fprintf(stderr, "ramp:\t %d: out: %8.4f, servo: %d \n", i, (double)outputs[i], (int)r_page_servos[i]); if (hrt_elapsed_time(&starttime) < RAMP_TIME_US && (r_page_servos[i] + 1 <= r_page_servo_disarmed[i] || r_page_servos[i] > servo_predicted[i])) { PX4_ERR("ramp servo value mismatch"); return 1; } /* check post ramp phase */ if (hrt_elapsed_time(&starttime) > RAMP_TIME_US && abs(servo_predicted[i] - r_page_servos[i]) > 2) { printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, (double)outputs[i], servo_predicted[i], (int)r_page_servos[i]); PX4_ERR("mixer violated predicted value"); return 1; } } usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { // printf("."); // fflush(stdout); } } //printf("\n"); /* load multirotor at once test */ mixer_group.reset(); #if !defined(CONFIG_ARCH_BOARD_SITL) filename = "/etc/mixers/quad_test.mix"; #else filename = "ROMFS/px4fmu_test/mixers/quad_test.mix"; #endif load_mixer_file(filename, &buf[0], sizeof(buf)); loaded = strlen(buf); //fprintf(stderr, "loaded: \n\"%s\"\n (%d chars)", &buf[0], loaded); unsigned mc_loaded = loaded; mixer_group.load_from_buf(&buf[0], mc_loaded); //PX4_INFO("complete buffer load: loaded %u mixers", mixer_group.count()); if (mixer_group.count() != 5) { PX4_ERR("FAIL: Quad test mixer load failed"); return 1; } //PX4_INFO("SUCCESS: No errors in mixer test"); return 0; }
void PX4FMU::cycle() { if (!_initialized) { /* force a reset of the update rate */ _current_update_rate = 0; _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); //_param_sub = orb_subscribe(ORB_ID(parameter_update)); /* initialize PWM limit lib */ pwm_limit_init(&_pwm_limit); update_pwm_rev_mask(); #ifdef RC_SERIAL_PORT _sbus_fd = sbus_init(RC_SERIAL_PORT, true); #endif _initialized = true; } if (_groups_subscribed != _groups_required) { subscribe(); _groups_subscribed = _groups_required; /* force setting update rate */ _current_update_rate = 0; } /* * Adjust actuator topic update rate to keep up with * the highest servo update rate configured. * * We always mix at max rate; some channels may update slower. */ unsigned max_rate = (_pwm_default_rate > _pwm_alt_rate) ? _pwm_default_rate : _pwm_alt_rate; if (_current_update_rate != max_rate) { _current_update_rate = max_rate; int update_rate_in_ms = int(1000 / _current_update_rate); /* reject faster than 500 Hz updates */ if (update_rate_in_ms < 2) { update_rate_in_ms = 2; } /* reject slower than 10 Hz updates */ if (update_rate_in_ms > 100) { update_rate_in_ms = 100; } //DEVICE_DEBUG("adjusted actuator update interval to %ums\n", update_rate_in_ms); for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { orb_set_interval(_control_subs[i], update_rate_in_ms); } } // set to current max rate, even if we are actually checking slower/faster _current_update_rate = max_rate; } /* check if anything updated */ //从mkblctrl-blctrl电子模块驱动拿数据,貌似没用到,而且poll里面也在等待定时器导致定时器卡死 int ret = 0;//::poll(_poll_fds, _poll_fds_num, 0); /* this would be bad... */ if (ret < 0) { DEVICE_LOG("poll error %d\n", ret); } else if (ret == 0) { /* timeout: no control data, switch to failsafe values */ // warnx("no PWM: failsafe\n"); } else { /* get controls for required topics */ unsigned poll_id = 0; for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { if (_poll_fds[poll_id].revents & POLLIN) { orb_copy(_control_topics[i], _control_subs[i], &_controls[i]); } poll_id++; } } /* can we mix? */ if (_mixers != NULL) { size_t num_outputs; switch (_mode) { case MODE_2PWM: num_outputs = 2; break; case MODE_4PWM: num_outputs = 4; break; case MODE_6PWM: num_outputs = 6; break; case MODE_8PWM: num_outputs = 8; break; default: num_outputs = 0; break; } /* do mixing */ float outputs[_max_actuators]; num_outputs = _mixers->mix(outputs, num_outputs, NULL); /* disable unused ports by setting their output to NaN */ for (size_t i = 0; i < sizeof(outputs) / sizeof(outputs[0]); i++) { if (i >= num_outputs) { outputs[i] = NAN_VALUE; } } uint16_t pwm_limited[_max_actuators]; /* the PWM limit call takes care of out of band errors, NaN and constrains */ pwm_limit_calc(_servo_armed, arm_nothrottle(), num_outputs, _reverse_pwm_mask, _disarmed_pwm, _min_pwm, _max_pwm, outputs, pwm_limited, &_pwm_limit); /* output to the servos */ for (size_t i = 0; i < num_outputs; i++) { up_pwm_servo_set(i, pwm_limited[i]); } publish_pwm_outputs(pwm_limited, num_outputs); } } /* check arming state */ bool updated = false; orb_check(_armed_sub, &updated); if (updated) { orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed); /* update the armed status and check that we're not locked down */ bool set_armed = (_armed.armed || _armed.prearmed) && !_armed.lockdown; if (_servo_armed != set_armed) { _servo_armed = set_armed; } /* update PWM status if armed or if disarmed PWM values are set */ bool pwm_on = (set_armed || _num_disarmed_set > 0); if (_pwm_on != pwm_on) { _pwm_on = pwm_on; up_pwm_servo_arm(pwm_on); } } /* TODO:F orb_check(_param_sub, &updated); if (updated) { parameter_update_s pupdate; orb_copy(ORB_ID(parameter_update), _param_sub, &pupdate); update_pwm_rev_mask(); } */ bool rc_updated = false; #ifdef RC_SERIAL_PORT bool sbus_failsafe, sbus_frame_drop; uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS]; uint16_t raw_rc_count; bool sbus_updated = sbus_input(_sbus_fd, &raw_rc_values[0], &raw_rc_count, &sbus_failsafe, &sbus_frame_drop, input_rc_s::RC_INPUT_MAX_CHANNELS); if (sbus_updated) { // we have a new PPM frame. Publish it. _rc_in.channel_count = raw_rc_count; if (_rc_in.channel_count > input_rc_s::RC_INPUT_MAX_CHANNELS) { _rc_in.channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS; } for (uint8_t i = 0; i < _rc_in.channel_count; i++) { _rc_in.values[i] = raw_rc_values[i]; // pilot_info("value[%d]=%d\n", i, _rc_in.values[i]); } _rc_in.timestamp_publication = hrt_absolute_time(); _rc_in.timestamp_last_signal = _rc_in.timestamp_publication; _rc_in.rc_ppm_frame_length = 0; _rc_in.rssi = (!sbus_frame_drop) ? RC_INPUT_RSSI_MAX : 0; _rc_in.rc_failsafe = false; _rc_in.rc_lost = false; _rc_in.rc_lost_frame_count = 0; _rc_in.rc_total_frame_count = 0; rc_updated = true; } #endif #ifdef HRT_PPM_CHANNEL // see if we have new PPM input data if ((ppm_last_valid_decode != _rc_in.timestamp_last_signal) && ppm_decoded_channels > 3) { // we have a new PPM frame. Publish it. _rc_in.channel_count = ppm_decoded_channels; if (_rc_in.channel_count > input_rc_s::RC_INPUT_MAX_CHANNELS) { _rc_in.channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS; } for (uint8_t i = 0; i < _rc_in.channel_count; i++) { _rc_in.values[i] = ppm_buffer[i]; } _rc_in.timestamp_publication = ppm_last_valid_decode; _rc_in.timestamp_last_signal = ppm_last_valid_decode; _rc_in.rc_ppm_frame_length = ppm_frame_length; _rc_in.rssi = RC_INPUT_RSSI_MAX; _rc_in.rc_failsafe = false; _rc_in.rc_lost = false; _rc_in.rc_lost_frame_count = 0; _rc_in.rc_total_frame_count = 0; rc_updated = true; } #endif if (rc_updated) { /* lazily advertise on first publication */ if (_to_input_rc == NULL) { _to_input_rc = orb_advertise(ORB_ID(input_rc), &_rc_in); } else { orb_publish(ORB_ID(input_rc), _to_input_rc, &_rc_in); } } // xTimerStart(_work, (2/portTICK_PERIOD_MS)); }