コード例 #1
0
ファイル: test_mixer.cpp プロジェクト: smithandrewc/Firmware
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");
}
コード例 #2
0
ファイル: mixer.cpp プロジェクト: Tiktiki/Firmware
void
mixer_tick(void)
{

	/* check that we are receiving fresh data from the FMU */
	if ((system_state.fmu_data_received_time == 0) ||
	    hrt_elapsed_time(&system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) {

		/* too long without FMU input, time to go to failsafe */
		if (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) {
			isr_debug(1, "AP RX timeout");
		}

		r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FMU_OK);
		r_status_alarms |= PX4IO_P_STATUS_ALARMS_FMU_LOST;

	} else {
		r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;

		/* this flag is never cleared once OK */
		r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED;
	}

	/* default to failsafe mixing - it will be forced below if flag is set */
	source = MIX_FAILSAFE;

	/*
	 * Decide which set of controls we're using.
	 */

	/* Do not mix if we have raw PWM and FMU is ok. */
	if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) &&
	    (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {

		if ((r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) > 0) {
			/* a channel based override has been
			 * triggered, with FMU active */
			source = MIX_OVERRIDE_FMU_OK;

		} else {
			/* don't actually mix anything - copy values from r_page_direct_pwm */
			source = MIX_NONE;
			memcpy(r_page_servos, r_page_direct_pwm, sizeof(uint16_t)*PX4IO_SERVO_COUNT);
		}

	} else {

		if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
		    (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) &&
		    (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {

			/* mix from FMU controls */
			source = MIX_FMU;
		}

		else if (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) {

			if (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) {

				/* if allowed, mix from RC inputs directly up to available rc channels */
				source = MIX_OVERRIDE_FMU_OK;

			} else {
				/* if allowed, mix from RC inputs directly */
				source = MIX_OVERRIDE;
			}
		}
	}

	/*
	 * Decide whether the servos should be armed right now.
	 *
	 * We must be armed, and we must have a PWM source; either raw from
	 * FMU or from the mixer.
	 *
	 */
	should_arm = (
			     /* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
			     /* and IO is armed */ 		  && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
			     /* and FMU is armed */ 		  && (
				     ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)
				      /* and there is valid input via or mixer */         && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK))
				     /* or direct PWM is set */               || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM)
				     /* or failsafe was set manually */	 || ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM)
						     && !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK))
			     )
		     );

	should_arm_nothrottle = (
					/* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
					/* and IO is armed */ 		  && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
					/* and there is valid input via or mixer */         && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK));

	should_always_enable_pwm = (r_setup_arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE)
				   && (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
				   && (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK);

	/*
	 * Check if failsafe termination is set - if yes,
	 * set the force failsafe flag once entering the first
	 * failsafe condition.
	 */
	if ( /* if we have requested flight termination style failsafe (noreturn) */
		(r_setup_arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE) &&
		/* and we ended up in a failsafe condition */
		(source == MIX_FAILSAFE) &&
		/* and we should be armed, so we intended to provide outputs */
		should_arm &&
		/* and FMU is initialized */
		(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED)) {
		r_setup_arming |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
	}

	/*
	 * Check if we should force failsafe - and do it if we have to
	 */
	if (r_setup_arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) {
		source = MIX_FAILSAFE;
	}

	/*
	 * Set failsafe status flag depending on mixing source
	 */
	if (source == MIX_FAILSAFE) {
		r_status_flags |= PX4IO_P_STATUS_FLAGS_FAILSAFE;

	} else {
		r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FAILSAFE);
	}

	/*
	 * Set simple mixer trim values
	 * (there should be a "dirty" flag to indicate that r_page_servo_control_trim has changed)
	 */
	mixer_group.set_trims(r_page_servo_control_trim, PX4IO_SERVO_COUNT);


	/*
	 * Run the mixers.
	 */
	if (source == MIX_FAILSAFE) {

		/* copy failsafe values to the servo outputs */
		for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
			r_page_servos[i] = r_page_servo_failsafe[i];

			/* safe actuators for FMU feedback */
			r_page_actuators[i] = FLOAT_TO_REG((r_page_servos[i] - 1500) / 600.0f);
		}


	} else if (source != MIX_NONE && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)
		   && !(r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN)) {

		float	outputs[PX4IO_SERVO_COUNT];
		unsigned mixed;

		if (REG_TO_FLOAT(r_setup_slew_max) > FLT_EPSILON) {
			// maximum value the ouputs of the multirotor mixer are allowed to change in this cycle
			// factor 2 is needed because actuator ouputs are in the range [-1,1]
			float delta_out_max = 2.0f * 1000.0f * dt / (r_page_servo_control_max[0] - r_page_servo_control_min[0]) / REG_TO_FLOAT(
						      r_setup_slew_max);
			mixer_group.set_max_delta_out_once(delta_out_max);
		}

		/* mix */
		/* update parameter for mc thrust model if it updated */
		if (update_mc_thrust_param) {
			mixer_group.set_thrust_factor(REG_TO_FLOAT(r_setup_thr_fac));
			update_mc_thrust_param = false;
		}

		/* mix */
		mixed = mixer_mix_threadsafe(&outputs[0], &r_mixer_limits);

		/* the pwm limit call takes care of out of band errors */
		pwm_limit_calc(should_arm, should_arm_nothrottle, mixed, r_setup_pwm_reverse, r_page_servo_disarmed,
			       r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);

		/* clamp unused outputs to zero */
		for (unsigned i = mixed; i < PX4IO_SERVO_COUNT; i++) {
			r_page_servos[i] = 0;
			outputs[i] = 0.0f;
		}

		/* store normalized outputs */
		for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
			r_page_actuators[i] = FLOAT_TO_REG(outputs[i]);
		}
	}

	/* set arming */
	bool needs_to_arm = (should_arm || should_arm_nothrottle || should_always_enable_pwm);

	/* lockdown means to send a valid pulse which disables the outputs */
	if (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN) {
		needs_to_arm = true;
	}

	if (needs_to_arm && !mixer_servos_armed) {
		/* need to arm, but not armed */
		up_pwm_servo_arm(true);
		mixer_servos_armed = true;
		r_status_flags |= PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED;
		isr_debug(5, "> PWM enabled");

	} else if (!needs_to_arm && mixer_servos_armed) {
		/* armed but need to disarm */
		up_pwm_servo_arm(false);
		mixer_servos_armed = false;
		r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED);
		isr_debug(5, "> PWM disabled");
	}

	if (mixer_servos_armed && (should_arm || should_arm_nothrottle)
	    && !(r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN)) {
		/* update the servo outputs. */
		for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
			up_pwm_servo_set(i, r_page_servos[i]);
		}

		/* set S.BUS1 or S.BUS2 outputs */

		if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT) {
			sbus2_output(_sbus_fd, r_page_servos, PX4IO_SERVO_COUNT);

		} else if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT) {
			sbus1_output(_sbus_fd, r_page_servos, PX4IO_SERVO_COUNT);
		}

	} else if (mixer_servos_armed && (should_always_enable_pwm
					  || (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN))) {
		/* set the disarmed servo outputs. */
		for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
			up_pwm_servo_set(i, r_page_servo_disarmed[i]);
			/* copy values into reporting register */
			r_page_servos[i] = r_page_servo_disarmed[i];
		}

		/* set S.BUS1 or S.BUS2 outputs */
		if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT) {
			sbus1_output(_sbus_fd, r_page_servo_disarmed, PX4IO_SERVO_COUNT);
		}

		if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT) {
			sbus2_output(_sbus_fd, r_page_servo_disarmed, PX4IO_SERVO_COUNT);
		}
	}
}
コード例 #3
0
ファイル: uart_esc.cpp プロジェクト: 13920381732/Firmware
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;

}
コード例 #4
0
ファイル: fmu.cpp プロジェクト: Bjarne-Madsen/Firmware
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);
}
コード例 #5
0
ファイル: mixer.cpp プロジェクト: junhongs/PIXHAWK_Serial
void
mixer_tick(void)
{

    /* check that we are receiving fresh data from the FMU */
    if ((system_state.fmu_data_received_time == 0) ||
            hrt_elapsed_time(&system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) {

        /* too long without FMU input, time to go to failsafe */
        if (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) {
            isr_debug(1, "AP RX timeout");
        }
        r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FMU_OK);
        r_status_alarms |= PX4IO_P_STATUS_ALARMS_FMU_LOST;

    } else {
        r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;

        /* this flag is never cleared once OK */
        r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED;
    }

    /* default to failsafe mixing - it will be forced below if flag is set */
    source = MIX_FAILSAFE;

    /*
     * Decide which set of controls we're using.
     */

    /* do not mix if RAW_PWM mode is on and FMU is good */
    if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) &&
            (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {

        /* don't actually mix anything - we already have raw PWM values */
        source = MIX_NONE;

    } else {

        if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
                (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) &&
                (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {

            /* mix from FMU controls */
            source = MIX_FMU;
        }

        if ( (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
                (r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
                (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) &&
                !(r_setup_arming & PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED) &&
                !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) &&
                /* do not enter manual override if we asked for termination failsafe and FMU is lost */
                !(r_setup_arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE)) {

            /* if allowed, mix from RC inputs directly */
            source = MIX_OVERRIDE;
        } else 	if ( (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
                     (r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
                     (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) &&
                     !(r_setup_arming & PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED) &&
                     (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {

            /* if allowed, mix from RC inputs directly up to available rc channels */
            source = MIX_OVERRIDE_FMU_OK;
        }
    }

    /*
     * Decide whether the servos should be armed right now.
     *
     * We must be armed, and we must have a PWM source; either raw from
     * FMU or from the mixer.
     *
     */
    should_arm = (
                     /* IO initialised without error */   (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
                     /* and IO is armed */ 		  && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
                     /* and FMU is armed */ 		  && (
                         ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)
                          /* and there is valid input via or mixer */         &&   (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) )
                         /* or direct PWM is set */               || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM)
                         /* or failsafe was set manually */	 || ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) && !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK))
                     )
                 );

    should_always_enable_pwm = (r_setup_arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE)
                               && (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
                               && (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK);

    /*
     * Check if failsafe termination is set - if yes,
     * set the force failsafe flag once entering the first
     * failsafe condition.
     */
    if (	/* if we have requested flight termination style failsafe (noreturn) */
        (r_setup_arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE) &&
        /* and we ended up in a failsafe condition */
        (source == MIX_FAILSAFE) &&
        /* and we should be armed, so we intended to provide outputs */
        should_arm &&
        /* and FMU is initialized */
        (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED)) {
        r_setup_arming |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
    }

    /*
     * Check if we should force failsafe - and do it if we have to
     */
    if (r_setup_arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) {
        source = MIX_FAILSAFE;
    }

    /*
     * Set failsafe status flag depending on mixing source
     */
    if (source == MIX_FAILSAFE) {
        r_status_flags |= PX4IO_P_STATUS_FLAGS_FAILSAFE;
    } else {
        r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FAILSAFE);
    }

    /*
     * Run the mixers.
     */
    if (source == MIX_FAILSAFE) {

        /* copy failsafe values to the servo outputs */
        for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
            r_page_servos[i] = r_page_servo_failsafe[i];

            /* safe actuators for FMU feedback */
            r_page_actuators[i] = FLOAT_TO_REG((r_page_servos[i] - 1500) / 600.0f);
        }


    } else if (source != MIX_NONE && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {

        float	outputs[PX4IO_SERVO_COUNT];
        unsigned mixed;

        /* mix */

        /* poor mans mutex */
        in_mixer = true;
        mixed = mixer_group.mix(&outputs[0], PX4IO_SERVO_COUNT, &r_mixer_limits);
        in_mixer = false;

        /* the pwm limit call takes care of out of band errors */
        pwm_limit_calc(should_arm, mixed, r_setup_pwm_reverse, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);

        for (unsigned i = mixed; i < PX4IO_SERVO_COUNT; i++)
            r_page_servos[i] = 0;

        for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
            r_page_actuators[i] = FLOAT_TO_REG(outputs[i]);
        }
    }

    /* set arming */
    bool needs_to_arm = (should_arm || should_always_enable_pwm);

    /* check any conditions that prevent arming */
    if (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN) {
        needs_to_arm = false;
    }
    if (!should_arm && !should_always_enable_pwm) {
        needs_to_arm = false;
    }

    if (needs_to_arm && !mixer_servos_armed) {
        /* need to arm, but not armed */
        up_pwm_servo_arm(true);
        mixer_servos_armed = true;
        r_status_flags |= PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED;
        isr_debug(5, "> PWM enabled");

    } else if (!needs_to_arm && mixer_servos_armed) {
        /* armed but need to disarm */
        up_pwm_servo_arm(false);
        mixer_servos_armed = false;
        r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED);
        isr_debug(5, "> PWM disabled");
    }

    if (mixer_servos_armed && should_arm) {
        /* update the servo outputs. */
        for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
            up_pwm_servo_set(i, r_page_servos[i]);
        }

        /* set S.BUS1 or S.BUS2 outputs */

        if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT) {
            sbus2_output(r_page_servos, PX4IO_SERVO_COUNT);
        } else if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT) {
            sbus1_output(r_page_servos, PX4IO_SERVO_COUNT);
        }

    } else if (mixer_servos_armed && should_always_enable_pwm) {
        /* set the disarmed servo outputs. */
        for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++)
            up_pwm_servo_set(i, r_page_servo_disarmed[i]);

        /* set S.BUS1 or S.BUS2 outputs */
        if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT)
            sbus1_output(r_page_servos, PX4IO_SERVO_COUNT);

        if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT)
            sbus2_output(r_page_servos, PX4IO_SERVO_COUNT);
    }
}
コード例 #6
0
ファイル: test_mixer.cpp プロジェクト: Kumru/Firmware
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;
}
コード例 #7
0
ファイル: test_mixer.cpp プロジェクト: dammstanger/Firmware
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;
}
コード例 #8
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));
}
コード例 #9
0
ファイル: mixer.cpp プロジェクト: smithandrewc/Firmware
void
mixer_tick(void)
{

	/* check that we are receiving fresh data from the FMU */
	if (hrt_elapsed_time(&system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) {

		/* too long without FMU input, time to go to failsafe */
		if (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) {
			isr_debug(1, "AP RX timeout");
		}
		r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FMU_OK);
		r_status_alarms |= PX4IO_P_STATUS_ALARMS_FMU_LOST;

	} else {
		r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;
	}

	/* default to failsafe mixing */
	source = MIX_FAILSAFE;

	/*
	 * Decide which set of controls we're using.
	 */

	/* do not mix if RAW_PWM mode is on and FMU is good */
	if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) &&
	        (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {

		/* don't actually mix anything - we already have raw PWM values */
		source = MIX_NONE;

	} else {

		if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
		     (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) &&
		     (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {

			/* mix from FMU controls */
			source = MIX_FMU;
		}

		if ( (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
		     (r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
		     (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) &&
		     !(r_setup_arming & PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED) &&
		     !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {

		 	/* if allowed, mix from RC inputs directly */
			source = MIX_OVERRIDE;
		} else 	if ( (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
		     (r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
		     (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) &&
		     !(r_setup_arming & PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED) &&
		     (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {

			/* if allowed, mix from RC inputs directly up to available rc channels */
			source = MIX_OVERRIDE_FMU_OK;
		}
	}

	/*
	 * Set failsafe status flag depending on mixing source
	 */
	if (source == MIX_FAILSAFE) {
		r_status_flags |= PX4IO_P_STATUS_FLAGS_FAILSAFE;
	} else {
		r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FAILSAFE);
	}

	/*
	 * Decide whether the servos should be armed right now.
	 *
	 * We must be armed, and we must have a PWM source; either raw from
	 * FMU or from the mixer.
	 *
	 * XXX correct behaviour for failsafe may require an additional case
	 * here.
	 */
	should_arm = (
		/* IO initialised without error */   (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
		/* and IO is armed */ 		  && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
		/* and FMU is armed */ 		  && (
							    ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)
		/* and there is valid input via or mixer */         &&   (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) )
		/* or direct PWM is set */               || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM)
		/* or failsafe was set manually */	 || (r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM)
						     )
	);

	should_always_enable_pwm = (r_setup_arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE)
						&& (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
						&& (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK);

	/*
	 * Run the mixers.
	 */
	if (source == MIX_FAILSAFE) {

		/* copy failsafe values to the servo outputs */
		for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
			r_page_servos[i] = r_page_servo_failsafe[i];

			/* safe actuators for FMU feedback */
			r_page_actuators[i] = FLOAT_TO_REG((r_page_servos[i] - 1500) / 600.0f);
		}


	} else if (source != MIX_NONE && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {

		float	outputs[PX4IO_SERVO_COUNT];
		unsigned mixed;

		/* mix */

		/* poor mans mutex */
		in_mixer = true;
		mixed = mixer_group.mix(&outputs[0], PX4IO_SERVO_COUNT);
		in_mixer = false;

		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);

		for (unsigned i = mixed; i < PX4IO_SERVO_COUNT; i++)
			r_page_servos[i] = 0;

		for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
			r_page_actuators[i] = FLOAT_TO_REG(outputs[i]);
		}
	}

	if ((should_arm || should_always_enable_pwm) && !mixer_servos_armed) {
		/* need to arm, but not armed */
		up_pwm_servo_arm(true);
		mixer_servos_armed = true;
		r_status_flags |= PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED;
		isr_debug(5, "> PWM enabled");

	} else if ((!should_arm && !should_always_enable_pwm) && mixer_servos_armed) {
		/* armed but need to disarm */
		up_pwm_servo_arm(false);
		mixer_servos_armed = false;
		r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED);
		isr_debug(5, "> PWM disabled");
	}

	if (mixer_servos_armed && should_arm) {
		/* update the servo outputs. */
		for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++)
			up_pwm_servo_set(i, r_page_servos[i]);

	} else if (mixer_servos_armed && should_always_enable_pwm) {
		/* set the disarmed servo outputs. */
		for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++)
			up_pwm_servo_set(i, r_page_servo_disarmed[i]);
	}
}