Ejemplo n.º 1
0
Archivo: sonar.c Proyecto: wmRosy/Flow
/**
  * @brief  Read out newest sonar data
  *
  * @param  sonar_value_filtered Filtered return value
  * @param  sonar_value_raw Raw return value
  */
bool sonar_read(float* sonar_value_filtered, float* sonar_value_raw)
{
	// check SR04 timeout
	if (sr04_initialized && trigger_time > 0 && get_boot_time_us() - trigger_time > SONAR_TIMEOUT)
	{
		printf("TIMEOUT\n");
		sonar_valid = false;
		trigger_time = 0;
	}
	
	if (private_sonar_initialized && timeout && isnan(distance))
	{
		sonar_valid = false;
	}
	
	/* getting new data with only around 10Hz */
	if (new_value) {
		sonar_filter();
		new_value = 0;
		sonar_measure_time = get_boot_time_us();
	}

	/* catch post-filter out of band values */
	if (x_post < SONAR_MIN || x_post > SONAR_MAX) {
		sonar_valid = false;
	}

	*sonar_value_filtered = x_post;
	*sonar_value_raw = sonar_raw;

	return sonar_valid;
}
Ejemplo n.º 2
0
/**
 * @brief Swap DMA image buffer addresses
 */
void dma_swap_buffers(void)
{
	/* check which buffer is in use */
	if (DMA_GetCurrentMemoryTarget(DMA2_Stream1))
	{
		/* swap dcmi image buffer */
		if (dcmi_image_buffer_unused == 1)
			DMA_MemoryTargetConfig(DMA2_Stream1, (uint32_t) dcmi_image_buffer_8bit_1, DMA_Memory_0);
		else if (dcmi_image_buffer_unused == 2)
			DMA_MemoryTargetConfig(DMA2_Stream1, (uint32_t) dcmi_image_buffer_8bit_2, DMA_Memory_0);
		else
			DMA_MemoryTargetConfig(DMA2_Stream1, (uint32_t) dcmi_image_buffer_8bit_3, DMA_Memory_0);

		int tmp_buffer = dcmi_image_buffer_memory0;
		dcmi_image_buffer_memory0 = dcmi_image_buffer_unused;
		dcmi_image_buffer_unused = tmp_buffer;
	}
	else
	{
		/* swap dcmi image buffer */
		if (dcmi_image_buffer_unused == 1)
			DMA_MemoryTargetConfig(DMA2_Stream1, (uint32_t) dcmi_image_buffer_8bit_1, DMA_Memory_1);
		else if (dcmi_image_buffer_unused == 2)
			DMA_MemoryTargetConfig(DMA2_Stream1, (uint32_t) dcmi_image_buffer_8bit_2, DMA_Memory_1);
		else
			DMA_MemoryTargetConfig(DMA2_Stream1, (uint32_t) dcmi_image_buffer_8bit_3, DMA_Memory_1);

		int tmp_buffer = dcmi_image_buffer_memory1;
		dcmi_image_buffer_memory1 = dcmi_image_buffer_unused;
		dcmi_image_buffer_unused = tmp_buffer;
	}

	/* set next time_between_images */
	cycle_time = get_boot_time_us() - time_last_frame;
	time_last_frame = get_boot_time_us();

	if(image_counter) // image was not fetched jet
	{
		time_between_next_images = time_between_next_images + cycle_time;
	}
	else
	{
		time_between_next_images = cycle_time;
	}

	/* set new image true and increment frame counter*/
	image_counter += 1;

	return;
}
Ejemplo n.º 3
0
Archivo: sonar.c Proyecto: wmRosy/Flow
/**
  * @brief  Triggers the sonar to measure the next value
  *
  * see datasheet for more info
  */
void sonar_trigger(){
	GPIO_SetBits(GPIOE, GPIO_Pin_8);
	
	if (sr04_initialized)
	{
		GPIO_SetBits(GPIOD, GPIO_Pin_14);
		// delay 10~20us
		volatile int time = TIM6->CNT;
		while(time == TIM6->CNT);
		time = TIM6->CNT;
		while(time == TIM6->CNT);
		
		GPIO_ResetBits(GPIOD, GPIO_Pin_14);
		
		trigger_time = get_boot_time_us();
	}
	
	if (private_sonar_initialized)
	{
		GPIO_ResetBits(GPIOA, GPIO_Pin_0);	// pull down comparator modifier
		reset_timer();
		
		GPIO_SetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_ResetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_SetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_ResetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_SetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_ResetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_SetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_ResetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_SetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_ResetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_SetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_ResetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_SetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_ResetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_SetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		GPIO_ResetBits(GPIOC, GPIO_Pin_4);
		delay_private();
		
		GPIO_SetBits(GPIOA, GPIO_Pin_0);	// release comparator modifier
		
	}
}
Ejemplo n.º 4
0
Archivo: sonar.c Proyecto: wmRosy/Flow
/**
  * @brief  Sonar interrupt handler
  */
void UART4_IRQHandler(void)
{
	if (USART_GetITStatus(UART4, USART_IT_RXNE) != RESET)
	{
		/* Read one byte from the receive data register */
		uint8_t data = (USART_ReceiveData(UART4));

		if (data == 'R')
		{
			/* this is the first char (start of transmission) */
			data_counter = 0;
			data_valid = 1;

			/* set sonar pin 4 to low -> we want triggered mode */
			GPIO_ResetBits(GPIOE, GPIO_Pin_8);
		}
		else if (0x30 <= data && data <= 0x39)
		{
			if (data_valid)
			{
				data_buffer[data_counter] = data;
				data_counter++;
			}
		}
		else if (data == 0x0D)
		{
			if (data_valid && data_counter == 4)
			{
				data_buffer[4] = 0;
				int temp = atoi(data_buffer);

				/* use real-world maximum ranges to cut off pure noise */
				if ((temp > SONAR_MIN*SONAR_SCALE) && (temp < SONAR_MAX*SONAR_SCALE))
				{
					/* it is in normal sensor range, take it */
					last_measure_time = measure_time;
					measure_time = get_boot_time_us();
					sonar_measure_time_interrupt = measure_time;
					dt = ((float)(measure_time - last_measure_time)) / 1000000.0f;

					valid_data = temp;
					sonar_mode = insert_sonar_value_and_get_mode_value(valid_data / SONAR_SCALE);
					new_value = 1;
					sonar_valid = true;
					
				} else {
					sonar_valid = false;
				}
			}

			data_valid = 0;
		}
		else
		{
			data_valid = 0;
		}
	}
}
Ejemplo n.º 5
0
Archivo: sonar.c Proyecto: wmRosy/Flow
void EXTI9_5_IRQHandler(void)
{
	// ignore any pulses if not triggered by caller
	if (sr04_initialized && trigger_time > 0)
	{
		volatile int time = TIM6->CNT;
		if(GPIOA->IDR & GPIO_Pin_8)
			rising_time = time;
		else if (rising_time > 0)
		{
			volatile int delta_time = time - rising_time;
			if (delta_time < 0)
				delta_time += 60000;
			int temp = delta_time * SOUND_SPEED/2;
			if (temp <= SONAR_MAX_SR04 && temp >= SONAR_MIN_SR04)
			{
				/* it is in normal sensor range, take it */
				last_measure_time = measure_time;
				measure_time = get_boot_time_us();
				sonar_measure_time_interrupt = measure_time;
				dt = ((float)(measure_time - last_measure_time)) / 1000000.0f;
				
				printf("R%d\n", temp);

				valid_data = temp;
				sonar_mode = insert_sonar_value_and_get_mode_value(valid_data / SONAR_SCALE);
				new_value = 1;
				sonar_valid = true;
				trigger_time = 0;
			}
			else
			{
				printf("R-1\n");
				sonar_valid = false;
			}
			rising_time = -1;
		}
		else
		{
			sonar_valid = false;
			rising_time = -1;	// no corresponding rising edge.
			trigger_time = -1;
		}
	}
	


	EXTI_ClearITPendingBit(EXTI_Line8);
}
Ejemplo n.º 6
0
Archivo: sonar.c Proyecto: wmRosy/Flow
void take_mesaure(float measure)
{
	last_measure_time = measure_time;
	measure_time = get_boot_time_us();
	sonar_measure_time_interrupt = measure_time;
	dt = ((float)(measure_time - last_measure_time)) / 1000000.0f;
	
	//printf("R%f\n", measure);

	valid_data = measure*1000;
	sonar_mode = insert_sonar_value_and_get_mode_value(measure);
	new_value = 1;
	sonar_valid = true;
	trigger_time = 0;
	
	update_i2c_sonar(measure);
}
Ejemplo n.º 7
0
/**
  * @brief  Read out newest sonar data
  *
  * @param  sonar_value_filtered Filtered return value
  * @param  sonar_value_raw Raw return value
  */
bool sonar_read(float* sonar_value_filtered, float* sonar_value_raw)
{
	/* getting new data with only around 10Hz */
	if (new_value) {
		sonar_filter();
		new_value = 0;
		sonar_measure_time = get_boot_time_us();
	}

	/* catch post-filter out of band values */
	if (x_post < SONAR_MIN || x_post > SONAR_MAX) {
		sonar_valid = false;
	}

	*sonar_value_filtered = x_post;
	*sonar_value_raw = sonar_raw;

	return sonar_valid;
}
Ejemplo n.º 8
0
void delay(uint16_t ms) {
    int32_t endt = get_boot_time_us() + (uint32_t)ms * 1000u;
    while ((endt - (int32_t)get_boot_time_us()) > 0);
}
Ejemplo n.º 9
0
uint32_t get_time_delta_us(uint32_t start)
{
    uint32_t now = get_boot_time_us();
    return calculate_time_delta_us(now, start);
}
Ejemplo n.º 10
0
Archivo: main.c Proyecto: leitwert/Flow
/**
  * @brief  Main function.
  */
int main(void)
{
	__enable_irq();
	snapshot_buffer = BuildCameraImageBuffer(snapshot_buffer_mem);

	/* load settings and parameters */
	global_data_reset_param_defaults();
	global_data_reset();

	/* init led */
	LEDInit(LED_ACT);
	LEDInit(LED_COM);
	LEDInit(LED_ERR);
	LEDOff(LED_ACT);
	LEDOff(LED_COM);
	LEDOff(LED_ERR);

	/* enable FPU on Cortex-M4F core */
	SCB_CPACR |= ((3UL << 10 * 2) | (3UL << 11 * 2)); /* set CP10 Full Access and set CP11 Full Access */

	/* init timers */
	timer_init();

	/* init usb */
	USBD_Init(	&USB_OTG_dev,
				USB_OTG_FS_CORE_ID,
				&USR_desc,
				&USBD_CDC_cb,
				&USR_cb);

	/* init mavlink */
	communication_init();

	/* initialize camera: */
	img_stream_param.size.x = FLOW_IMAGE_SIZE;
	img_stream_param.size.y = FLOW_IMAGE_SIZE;
	img_stream_param.binning = 4;
	{
		camera_image_buffer buffers[5] = {
			BuildCameraImageBuffer(image_buffer_8bit_1),
			BuildCameraImageBuffer(image_buffer_8bit_2),
			BuildCameraImageBuffer(image_buffer_8bit_3),
			BuildCameraImageBuffer(image_buffer_8bit_4),
			BuildCameraImageBuffer(image_buffer_8bit_5)
		};
		camera_init(&cam_ctx, mt9v034_get_sensor_interface(), dcmi_get_transport_interface(), 
					mt9v034_get_clks_per_row(64, 4) * 1, mt9v034_get_clks_per_row(64, 4) * 64, 2.0,
					&img_stream_param, buffers, 5);
	}

	/* gyro config */
	gyro_config();

	/* usart config*/
	usart_init();

    /* i2c config*/
    i2c_init();

	/* sonar config*/
	float sonar_distance_filtered = 0.0f; // distance in meter
	float sonar_distance_raw = 0.0f; // distance in meter
	bool distance_valid = false;
	sonar_config();

	/* reset/start timers */
	timer_register(sonar_update_fn, SONAR_POLL_MS);
	timer_register(system_state_send_fn, SYSTEM_STATE_MS);
	timer_register(system_receive_fn, SYSTEM_STATE_MS / 2);
	timer_register(send_params_fn, PARAMS_MS);
	timer_register(send_video_fn, global_data.param[PARAM_VIDEO_RATE]);
	timer_register(take_snapshot_fn, 500);
	//timer_register(switch_params_fn, 2000);

	/* variables */
	uint32_t counter = 0;

	result_accumulator_ctx mavlink_accumulator;

	result_accumulator_init(&mavlink_accumulator);
	
	uint32_t fps_timing_start = get_boot_time_us();
	uint16_t fps_counter = 0;
	uint16_t fps_skipped_counter = 0;
	
	uint32_t last_frame_index = 0;
	
	/* main loop */
	while (1)
	{
		/* check timers */
		timer_check();
		
		if (snap_capture_done) {
			snap_capture_done = false;
			camera_snapshot_acknowledge(&cam_ctx);
			snap_ready = true;
			if (snap_capture_success) {
				/* send the snapshot! */
				LEDToggle(LED_COM);
				mavlink_send_image(&snapshot_buffer);
			}
		}

		/* calculate focal_length in pixel */
		const float focal_length_px = (global_data.param[PARAM_FOCAL_LENGTH_MM]) / (4.0f * 0.006f); //original focal lenght: 12mm pixelsize: 6um, binning 4 enabled

		/* new gyroscope data */
		float x_rate_sensor, y_rate_sensor, z_rate_sensor;
		int16_t gyro_temp;
		gyro_read(&x_rate_sensor, &y_rate_sensor, &z_rate_sensor,&gyro_temp);

		/* gyroscope coordinate transformation to flow sensor coordinates */
		float x_rate =   y_rate_sensor; // change x and y rates
		float y_rate = - x_rate_sensor;
		float z_rate =   z_rate_sensor; // z is correct

		/* get sonar data */
		distance_valid = sonar_read(&sonar_distance_filtered, &sonar_distance_raw);
		/* reset to zero for invalid distances */
		if (!distance_valid) {
			sonar_distance_filtered = 0.0f;
			sonar_distance_raw = 0.0f;
		}

		bool use_klt = global_data.param[PARAM_ALGORITHM_CHOICE] != 0;

		uint32_t start_computations = 0;
		
		/* get recent images */
		camera_image_buffer *frames[2];
		camera_img_stream_get_buffers(&cam_ctx, frames, 2, true);
		
		start_computations = get_boot_time_us();
		
		int frame_delta = ((int32_t)frames[0]->frame_number - (int32_t)last_frame_index);
		last_frame_index = frames[0]->frame_number;
		fps_skipped_counter += frame_delta - 1;
		
		flow_klt_image *klt_images[2] = {NULL, NULL};
		{
			/* make sure that the new images get the correct treatment */
			/* this algorithm will still work if both images are new */
			int i;
			bool used_klt_image[2] = {false, false};
			for (i = 0; i < 2; ++i) {
				if (frames[i]->frame_number != frames[i]->meta) {
					// the image is new. apply pre-processing:
					/* filter the new image */
					if (global_data.param[PARAM_ALGORITHM_IMAGE_FILTER]) {
						filter_image(frames[i]->buffer, frames[i]->param.p.size.x);
					}
					/* update meta data to mark it as an up-to date image: */
					frames[i]->meta = frames[i]->frame_number;
				} else {
					// the image has the preprocessing already applied.
					if (use_klt) {
						int j;
						/* find the klt image that matches: */
						for (j = 0; j < 2; ++j) {
							if (flow_klt_images[j].meta == frames[i]->frame_number) {
								used_klt_image[j] = true;
								klt_images[i] = &flow_klt_images[j];
							}
						}
					}
				}
			}
			if (use_klt) {
				/* only for KLT: */
				/* preprocess the images if they are not yet preprocessed */
				for (i = 0; i < 2; ++i) {
					if (klt_images[i] == NULL) {
						// need processing. find unused KLT image:
						int j;
						for (j = 0; j < 2; ++j) {
							if (!used_klt_image[j]) {
								used_klt_image[j] = true;
								klt_images[i] = &flow_klt_images[j];
								break;
							}
						}
						klt_preprocess_image(frames[i]->buffer, klt_images[i]);
					}
				}
			}
		}
		
		float frame_dt = (frames[0]->timestamp - frames[1]->timestamp) * 0.000001f;

		/* compute gyro rate in pixels and change to image coordinates */
		float x_rate_px = - y_rate * (focal_length_px * frame_dt);
		float y_rate_px =   x_rate * (focal_length_px * frame_dt);
		float z_rate_fr = - z_rate * frame_dt;

		/* compute optical flow in pixels */
		flow_raw_result flow_rslt[32];
		uint16_t flow_rslt_count = 0;
		if (!use_klt) {
			flow_rslt_count = compute_flow(frames[1]->buffer, frames[0]->buffer, x_rate_px, y_rate_px, z_rate_fr, flow_rslt, 32);
		} else {
			flow_rslt_count =  compute_klt(klt_images[1], klt_images[0], x_rate_px, y_rate_px, z_rate_fr, flow_rslt, 32);
		}

		/* calculate flow value from the raw results */
		float pixel_flow_x;
		float pixel_flow_y;
		float outlier_threshold = global_data.param[PARAM_ALGORITHM_OUTLIER_THR_RATIO];
		float min_outlier_threshold = 0;
		if(global_data.param[PARAM_ALGORITHM_CHOICE] == 0)
		{
			min_outlier_threshold = global_data.param[PARAM_ALGORITHM_OUTLIER_THR_BLOCK];
		}else
		{
			min_outlier_threshold = global_data.param[PARAM_ALGORITHM_OUTLIER_THR_KLT];
		}
		uint8_t qual = flow_extract_result(flow_rslt, flow_rslt_count, &pixel_flow_x, &pixel_flow_y, 
							outlier_threshold,  min_outlier_threshold);

		/* create flow image if needed (previous_image is not needed anymore)
		 * -> can be used for debugging purpose
		 */
		previous_image = frames[1];
		if (global_data.param[PARAM_USB_SEND_VIDEO])
		{
			uint16_t frame_size = global_data.param[PARAM_IMAGE_WIDTH];
			uint8_t *prev_img = previous_image->buffer;
			for (int i = 0; i < flow_rslt_count; i++) {
				if (flow_rslt[i].quality > 0) {
					prev_img[flow_rslt[i].at_y * frame_size + flow_rslt[i].at_x] = 255;
					int ofs = (int)floor(flow_rslt[i].at_y + flow_rslt[i].y * 2 + 0.5f) * frame_size + (int)floor(flow_rslt[i].at_x + flow_rslt[i].x * 2 + 0.5f);
					if (ofs >= 0 && ofs < frame_size * frame_size) {
						prev_img[ofs] = 200;
					}
				}
			}
		}

		/* return the image buffers */
		camera_img_stream_return_buffers(&cam_ctx, frames, 2);
		
		/* decide which distance to use */
		float ground_distance = 0.0f;

		if(global_data.param[PARAM_SONAR_FILTERED])
		{
			ground_distance = sonar_distance_filtered;
		}
		else
		{
			ground_distance = sonar_distance_raw;
		}

		/* update I2C transmit buffer */
		update_TX_buffer(frame_dt, 
						 x_rate, y_rate, z_rate, gyro_temp, 
						 qual, pixel_flow_x, pixel_flow_y, 1.0f / focal_length_px, 
						 distance_valid, ground_distance, get_time_delta_us(get_sonar_measure_time()));

		/* accumulate the results */
		result_accumulator_feed(&mavlink_accumulator, frame_dt, 
								x_rate, y_rate, z_rate, gyro_temp, 
								qual, pixel_flow_x, pixel_flow_y, 1.0f / focal_length_px, 
								distance_valid, ground_distance, get_time_delta_us(get_sonar_measure_time()));

		uint32_t computaiton_time_us = get_time_delta_us(start_computations);

		counter++;
		fps_counter++;

        /* serial mavlink  + usb mavlink output throttled */
		if (counter % (uint32_t)global_data.param[PARAM_FLOW_SERIAL_THROTTLE_FACTOR] == 0)//throttling factor
		{
			float fps = 0;
			float fps_skip = 0;
			if (fps_counter + fps_skipped_counter > 100) {
				uint32_t dt = get_time_delta_us(fps_timing_start);
				fps_timing_start += dt;
				fps = (float)fps_counter / ((float)dt * 1e-6f);
				fps_skip = (float)fps_skipped_counter / ((float)dt * 1e-6f);
				fps_counter = 0;
				fps_skipped_counter = 0;

				mavlink_msg_debug_vect_send(MAVLINK_COMM_2, "TIMING", get_boot_time_us(), computaiton_time_us, fps, fps_skip);
			}
			mavlink_msg_debug_vect_send(MAVLINK_COMM_2, "EXPOSURE", get_boot_time_us(), 
					frames[0]->param.exposure, frames[0]->param.analog_gain, cam_ctx.last_brightness);
			
			/* calculate the output values */
			result_accumulator_output_flow output_flow;
			result_accumulator_output_flow_rad output_flow_rad;
			int min_valid_ratio = global_data.param[PARAM_ALGORITHM_MIN_VALID_RATIO];
			result_accumulator_calculate_output_flow(&mavlink_accumulator, min_valid_ratio, &output_flow);
			result_accumulator_calculate_output_flow_rad(&mavlink_accumulator, min_valid_ratio, &output_flow_rad);

			// send flow
			mavlink_msg_optical_flow_send(MAVLINK_COMM_0, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
					output_flow.flow_x, output_flow.flow_y,
					output_flow.flow_comp_m_x, output_flow.flow_comp_m_y, 
					output_flow.quality, output_flow.ground_distance);

			mavlink_msg_optical_flow_rad_send(MAVLINK_COMM_0, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
					output_flow_rad.integration_time, 
					output_flow_rad.integrated_x, output_flow_rad.integrated_y,
					output_flow_rad.integrated_xgyro, output_flow_rad.integrated_ygyro, output_flow_rad.integrated_zgyro,
					output_flow_rad.temperature, output_flow_rad.quality,
					output_flow_rad.time_delta_distance_us,output_flow_rad.ground_distance);

			if (global_data.param[PARAM_USB_SEND_FLOW] && (output_flow.quality > 0 || global_data.param[PARAM_USB_SEND_QUAL_0]))
			{
				mavlink_msg_optical_flow_send(MAVLINK_COMM_2, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
						output_flow.flow_x, output_flow.flow_y,
						output_flow.flow_comp_m_x, output_flow.flow_comp_m_y, 
						output_flow.quality, output_flow.ground_distance);

				mavlink_msg_optical_flow_rad_send(MAVLINK_COMM_2, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
						output_flow_rad.integration_time, 
						output_flow_rad.integrated_x, output_flow_rad.integrated_y,
						output_flow_rad.integrated_xgyro, output_flow_rad.integrated_ygyro, output_flow_rad.integrated_zgyro,
						output_flow_rad.temperature, output_flow_rad.quality,
						output_flow_rad.time_delta_distance_us,output_flow_rad.ground_distance);
			}

			if(global_data.param[PARAM_USB_SEND_GYRO])
			{
				mavlink_msg_debug_vect_send(MAVLINK_COMM_2, "GYRO", get_boot_time_us(), x_rate, y_rate, z_rate);
			}

			result_accumulator_reset(&mavlink_accumulator);
		}

		/* forward flow from other sensors */
		if (counter % 2)
		{
			communication_receive_forward();
		}
	}
}
Ejemplo n.º 11
0
/**
  * @brief  Main function.
  */
int main(void)
{
	/* load settings and parameters */
	global_data_reset_param_defaults();
	global_data_reset();

	/* init led */
	LEDInit(LED_ACT);
	LEDInit(LED_COM);
	LEDInit(LED_ERR);
	LEDOff(LED_ACT);
	LEDOff(LED_COM);
	LEDOff(LED_ERR);

	/* enable FPU on Cortex-M4F core */
	SCB_CPACR |= ((3UL << 10 * 2) | (3UL << 11 * 2)); /* set CP10 Full Access and set CP11 Full Access */

	/* init clock */
	if (SysTick_Config(SystemCoreClock / 100000))/*set timer to trigger interrupt every 10 microsecond */
	{
		/* capture clock error */
		LEDOn(LED_ERR);
		while (1);
	}

	/* init usb */
	USBD_Init(	&USB_OTG_dev,
				USB_OTG_FS_CORE_ID,
				&USR_desc,
				&USBD_CDC_cb,
				&USR_cb);

	/* init mavlink */
	communication_init();

	/* enable image capturing */
	enable_image_capture();

	/* gyro config */
	gyro_config();

	/* init and clear fast image buffers */
	for (int i = 0; i < global_data.param[PARAM_IMAGE_WIDTH] * global_data.param[PARAM_IMAGE_HEIGHT]; i++)
	{
		image_buffer_8bit_1[i] = 0;
		image_buffer_8bit_2[i] = 0;
	}

	uint8_t * current_image = image_buffer_8bit_1;
	uint8_t * previous_image = image_buffer_8bit_2;
    
    uint8_t   current_image1[64][64];
    uint8_t   current_image2[64][64];
    uint8_t   current_image3[64][64];
    uint8_t   current_image4[64][64];
    uint8_t   previous_image1[64][64];
    uint8_t   previous_image2[64][64];
    uint8_t   previous_image3[64][64];
    uint8_t   previous_image4[64][64];
    for(int i=0;i<64;++i)
    {
        for(int j=0;j<64;++j)
        {
            current_image1[i][j]=0;
            previous_image1[i][j]=0;
            current_image2[i][j]=0;
            previous_image2[i][j]=0;
            current_image3[i][j]=0;
            previous_image3[i][j]=0;
            current_image4[i][j]=0;
            previous_image4[i][j]=0;
        }
    }
    
    uint8_t ourImage[OurSize];
    for(int i=0;i<OurSize;++i)
    {
        ourImage[i]=0;
    }
    
	/* usart config*/
	usart_init();

    /* i2c config*/
    i2c_init();

	/* sonar config*/
	float sonar_distance_filtered = 0.0f; // distance in meter
	float sonar_distance_raw = 0.0f; // distance in meter
	bool distance_valid = false;
	sonar_config();

	/* reset/start timers */
	timer[TIMER_SONAR] = SONAR_TIMER_COUNT;
	timer[TIMER_SYSTEM_STATE] = SYSTEM_STATE_COUNT;
	timer[TIMER_RECEIVE] = SYSTEM_STATE_COUNT / 2;
	timer[TIMER_PARAMS] = PARAMS_COUNT;
	timer[TIMER_IMAGE] = global_data.param[PARAM_VIDEO_RATE];

	/* variables */
	uint32_t counter = 0;
	uint8_t qual = 0;

	/* bottom flow variables */
	float pixel_flow_x = 0.0f;
	float pixel_flow_y = 0.0f;
	float pixel_flow_x_sum = 0.0f;
	float pixel_flow_y_sum = 0.0f;
	float velocity_x_sum = 0.0f;
	float velocity_y_sum = 0.0f;
	float velocity_x_lp = 0.0f;
	float velocity_y_lp = 0.0f;
	int valid_frame_count = 0;
	int pixel_flow_count = 0;
	float pixel_flow_x_lp = 0.0f;
	float pixel_flow_y_lp = 0.0f;

	static float accumulated_flow_x = 0;
	static float accumulated_flow_y = 0;
	static float accumulated_gyro_x = 0;
	static float accumulated_gyro_y = 0;
	static float accumulated_gyro_z = 0;
	static uint16_t accumulated_framecount = 0;
	static uint16_t accumulated_quality = 0;
	static uint32_t integration_timespan = 0;
	static uint32_t lasttime = 0;
	uint32_t time_since_last_sonar_update= 0;

	static float last_vel_x = 0;
	static float last_vel_y = 0;
	float vel_x = 0, vel_y = 0;

    //Change
    int count=1;
    //int gyroCount=1;
    uint8_t * tmp_image1 = *previous_image;
    uint8_t * tmp_image2 = *current_image;
    float x_temprate=0;
    float y_temprate=0;
    float z_temprate=0;
    
    int defCount=3;
    
    
    
    for (uint16_t pixel = 0; pixel < global_data.param[PARAM_IMAGE_WIDTH] * global_data.param[PARAM_IMAGE_HEIGHT]; pixel++)
    {
        *(tmp_image1+pixel)=0;
        *(tmp_image2+pixel)=0;
    }
    uint16_t image_sum1=0;
    uint16_t image_sum2=0;
    uint16_t image_sum3=0;
    uint16_t image_sum4=0;
    //EndChange


	/* main loop */
	while (1)
	{
        
        
        uint16_t image_size = global_data.param[PARAM_IMAGE_WIDTH] * global_data.param[PARAM_IMAGE_HEIGHT];
        
		/* reset flow buffers if needed */
		if(buffer_reset_needed)
		{
			buffer_reset_needed = 0;
			for (int i = 0; i < global_data.param[PARAM_IMAGE_WIDTH] * global_data.param[PARAM_IMAGE_HEIGHT]; i++)
			{
				image_buffer_8bit_1[i] = 0;
				image_buffer_8bit_2[i] = 0;
			}
			delay(500);
			continue;
		}

		/* calibration routine */
		if(global_data.param[PARAM_VIDEO_ONLY])
		{
			while(global_data.param[PARAM_VIDEO_ONLY])
			{
				dcmi_restart_calibration_routine();

				/* waiting for first quarter of image */
				while(get_frame_counter() < 2){}
				dma_copy_image_buffers(&current_image, &previous_image, FULL_IMAGE_SIZE, 1);

				/* waiting for second quarter of image */
				while(get_frame_counter() < 3){}
				dma_copy_image_buffers(&current_image, &previous_image, FULL_IMAGE_SIZE, 1);

				/* waiting for all image parts */
				while(get_frame_counter() < 4){}

				send_calibration_image(&previous_image, &current_image);

				if (global_data.param[PARAM_SYSTEM_SEND_STATE])
					communication_system_state_send();

				communication_receive_usb();
				debug_message_send_one();
				communication_parameter_send();

				LEDToggle(LED_COM);
			}

			dcmi_restart_calibration_routine();
			LEDOff(LED_COM);
		}

        
        //StartChange
        if(count<=defCount)
        {
            if(count==1)
            {
                for (uint16_t pixel = 0; pixel < image_size; pixel++)
                {
                    image_sum1+=*(previous_image+pixel);
                }
                for (uint16_t pixel = 0; pixel < image_size; pixel++)
                {
                    *(tmp_image1+pixel)=(uint8_t)(*(previous_image+pixel));
                }
            }
            else
            {
                for (uint16_t pixel = 0; pixel < image_size; pixel++)
                {
                    image_sum2+=*(previous_image+pixel);
                }
                if(image_sum1<image_sum2)
                {
                    image_sum1=image_sum2;
                    for (uint16_t pixel = 0; pixel < image_size; pixel++)
                    {
                        *(tmp_image1+pixel)=(uint8_t)(*(previous_image+pixel));
                    }
                }
                image_sum2=0;
            }
        }
        if(count>defCount&&count<=2*defCount)
        {
//            uint16_t image_sum1=0;
//            uint16_t image_sum2=0;
            if(count==defCount+1)
            {
                for (uint16_t pixel = 0; pixel < image_size; pixel++)
                {
                    image_sum3+=*(current_image+pixel);
                }
                for (uint16_t pixel = 0; pixel < image_size; pixel++)
                {
                    *(tmp_image2+pixel)=(uint8_t)(*(previous_image+pixel));
                }
            }
            else
            {
                for (uint16_t pixel = 0; pixel < image_size; pixel++)
                {
                    image_sum4+=*(current_image+pixel);
                }
                if(image_sum3<image_sum4)
                {
                    image_sum3=image_sum4;
                    for (uint16_t pixel = 0; pixel < image_size; pixel++)
                    {
                        *(tmp_image2+pixel)=(uint8_t)(*(previous_image+pixel));
                    }
                }
                image_sum4=0;
            }
        }
//        if(count<=defCount)
//        {
//            for (uint16_t pixel = 0; pixel < image_size; pixel++)
//            {
//                *(tmp_image1+pixel)+=(uint8_t)(*(previous_image+pixel)/defCount);
//            }
//        }
//        if(count>defCount&&count<=2*defCount)
//        {
//            for (uint16_t pixel = 0; pixel < image_size; pixel++)
//            {
//                *(tmp_image2+pixel)+=(uint8_t)(*(current_image+pixel)/defCount);
//            }
//           
//        }
        count++;
        if(count==2*defCount+1)
        {
            
            /* new gyroscope data */
            float x_rate_sensor, y_rate_sensor, z_rate_sensor;
            int16_t gyro_temp;
            gyro_read(&x_rate_sensor, &y_rate_sensor, &z_rate_sensor,&gyro_temp);
            
            /* gyroscope coordinate transformation */
            x_temprate += y_rate_sensor/(2*defCount); // change x and y rates
            y_temprate += - x_rate_sensor/(2*defCount);
            z_temprate += z_rate_sensor/(2*defCount); // z is correct
            
            /* calculate focal_length in pixel */
            const float focal_length_px = (global_data.param[PARAM_FOCAL_LENGTH_MM]) / (4.0f * 6.0f) * 1000.0f; //original focal lenght: 12mm pixelsize: 6um, binning 4 enabled
            
            /* get sonar data */
            distance_valid = sonar_read(&sonar_distance_filtered, &sonar_distance_raw);
            
            /* reset to zero for invalid distances */
            if (!distance_valid) {
                sonar_distance_filtered = 0.0f;
                sonar_distance_raw = 0.0f;
            }
            
            float x_rate = x_temprate; // change x and y rates
            float y_rate = - y_temprate;
            float z_rate = z_temprate; // z is correct
            x_temprate =0.0f;
            y_temprate =0.0f;
            z_temprate =0.0f;
            
//            /* calculate focal_length in pixel */
//            const float focal_length_px = (global_data.param[PARAM_FOCAL_LENGTH_MM]) / (4.0f * 6.0f) * 1000.0f; //original focal lenght: 12mm pixelsize: 6um, binning 4 enabled
//            
//            /* get sonar data */
//            distance_valid = sonar_read(&sonar_distance_filtered, &sonar_distance_raw);
            
            
            *previous_image=tmp_image1;
            *current_image=tmp_image2;
            count=1;
            for (uint16_t pixel = 0; pixel < image_size; pixel++)
            {
                *(tmp_image1+pixel)=0;
                *(tmp_image2+pixel)=0;
            }
            image_sum1=0;
            image_sum2=0;
            image_sum3=0;
            image_sum4=0;
            /* compute optical flow */
            if(global_data.param[PARAM_SENSOR_POSITION] == BOTTOM)
            {
                /* copy recent image to faster ram */
                dma_copy_image_buffers(&current_image, &previous_image, image_size, 1);
                
                for(int i=0;i<64;++i)
                {
                    for(int j=0;j<64;++j)
                    {
                        previous_image1[i][j]=*(previous_image+64*i+j);
                        current_image1[i][j]=*(current_image+64*i+j);
                    }
                }
                
                /* compute optical flow */
                qual = compute_flow(previous_image, current_image, x_rate, y_rate, z_rate, &pixel_flow_x, &pixel_flow_y);
                
                /*
                 * real point P (X,Y,Z), image plane projection p (x,y,z), focal-length f, distance-to-scene Z
                 * x / f = X / Z
                 * y / f = Y / Z
                 */
                float flow_compx = pixel_flow_x / focal_length_px / (get_time_between_images() / 1000000.0f);
                float flow_compy = pixel_flow_y / focal_length_px / (get_time_between_images() / 1000000.0f);
                
                /* integrate velocity and output values only if distance is valid */
                if (distance_valid)
                {
                    /* calc velocity (negative of flow values scaled with distance) */
                    float new_velocity_x = - flow_compx * sonar_distance_filtered;
                    float new_velocity_y = - flow_compy * sonar_distance_filtered;
                    
                    time_since_last_sonar_update = (get_boot_time_us()- get_sonar_measure_time());
                    
                    if (qual > 0)
                    {
                        velocity_x_sum += new_velocity_x;
                        velocity_y_sum += new_velocity_y;
                        valid_frame_count++;
                        
                        uint32_t deltatime = (get_boot_time_us() - lasttime);
                        integration_timespan += deltatime;
                        accumulated_flow_x += pixel_flow_y  / focal_length_px * 1.0f; //rad axis swapped to align x flow around y axis
                        accumulated_flow_y += pixel_flow_x  / focal_length_px * -1.0f;//rad
                        accumulated_gyro_x += x_rate * deltatime / 1000000.0f;	//rad
                        accumulated_gyro_y += y_rate * deltatime / 1000000.0f;	//rad
                        accumulated_gyro_z += z_rate * deltatime / 1000000.0f;	//rad
                        accumulated_framecount++;
                        accumulated_quality += qual;
                        
                        /* lowpass velocity output */
                        velocity_x_lp = global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW] * new_velocity_x +
                        (1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * velocity_x_lp;
                        velocity_y_lp = global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW] * new_velocity_y +
                        (1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * velocity_y_lp;
                    }
                    else
                    {
                        /* taking flow as zero */
                        velocity_x_lp = (1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * velocity_x_lp;
                        velocity_y_lp = (1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * velocity_y_lp;
                    }
                }
                else
                {
                    /* taking flow as zero */
                    velocity_x_lp = (1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * velocity_x_lp;
                    velocity_y_lp = (1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * velocity_y_lp;
                }
                //update lasttime
                lasttime = get_boot_time_us();
                
                pixel_flow_x_sum += pixel_flow_x;
                pixel_flow_y_sum += pixel_flow_y;
                pixel_flow_count++;
                
            }
            
            counter++;
            
            if(global_data.param[PARAM_SENSOR_POSITION] == BOTTOM)
            {
                /* send bottom flow if activated */
                
                float ground_distance = 0.0f;
                
                
                if(global_data.param[PARAM_SONAR_FILTERED])
                {
                    ground_distance = sonar_distance_filtered;
                }
                else
                {
                    ground_distance = sonar_distance_raw;
                }
                
                if(global_data.param[PARAM_BOTTOM_FLOW_LP_FILTERED])
                {
                    /* lowpass velocity output */
                    pixel_flow_x_lp = global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW] * pixel_flow_x +
                    (1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * pixel_flow_x_lp;
                    pixel_flow_y_lp = global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW] * pixel_flow_y +
                    (1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * pixel_flow_y_lp;
                }
                else
                {
                    pixel_flow_x_lp = pixel_flow_x;
                    pixel_flow_y_lp = pixel_flow_y;
                }
                //update I2C transmitbuffer
                if(valid_frame_count>0)
                {
                    update_TX_buffer(pixel_flow_x_lp, pixel_flow_y_lp, velocity_x_sum/valid_frame_count, velocity_y_sum/valid_frame_count, qual,
                                     ground_distance, x_rate, y_rate, z_rate, gyro_temp);
                    last_vel_x = velocity_x_sum/valid_frame_count;
                    last_vel_y = velocity_y_sum/valid_frame_count;
                    vel_x = last_vel_x;
                    vel_y = last_vel_y;
                }
                else
                {
                    /*
                     update_TX_buffer(pixel_flow_x_lp, pixel_flow_y_lp, last_vel_x, last_vel_y, qual,
                     ground_distance, x_rate, y_rate, z_rate, gyro_temp);
                     vel_x = 0;
                     vel_y = 0;
                     */
                }
                
                //serial mavlink  + usb mavlink output throttled
                if (counter % (uint32_t)global_data.param[PARAM_BOTTOM_FLOW_SERIAL_THROTTLE_FACTOR] == 0)//throttling factor
                {
                    float flow_comp_m_x = 0.0f;
                    float flow_comp_m_y = 0.0f;
                    
                    if(global_data.param[PARAM_BOTTOM_FLOW_LP_FILTERED])
                    {
                        flow_comp_m_x = velocity_x_lp;
                        flow_comp_m_y = velocity_y_lp;
                    }
                    else
                    {
                        if(valid_frame_count>0)
                        {
                            flow_comp_m_x = velocity_x_sum/valid_frame_count;
                            flow_comp_m_y = velocity_y_sum/valid_frame_count;
                        }
                        else
                        {
                            flow_comp_m_x = 0.0f;
                            flow_comp_m_y = 0.0f;
                        }
                    }
                    
                    
                    // send flow
                    mavlink_msg_optical_flow_send(MAVLINK_COMM_0, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
                                                  pixel_flow_x_sum * 10.0f, pixel_flow_y_sum * 10.0f,
                                                  flow_comp_m_x, flow_comp_m_y, qual, ground_distance);
                    
                    
                    mavlink_msg_optical_flow_rad_send(MAVLINK_COMM_0, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
                                                      integration_timespan, accumulated_flow_x, accumulated_flow_y,
                                                      accumulated_gyro_x, accumulated_gyro_y, accumulated_gyro_z,
                                                      gyro_temp, accumulated_quality/accumulated_framecount,
                                                      time_since_last_sonar_update,ground_distance);
                    
                    /*
                     mavlink_msg_optical_flow_rad_send(MAVLINK_COMM_0, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
                     integration_timespan, accumulated_flow_x, accumulated_flow_y,
                     vel_x, vel_y, accumulated_gyro_z,
                     gyro_temp, accumulated_quality/accumulated_framecount,
                     time_since_last_sonar_update,ground_distance);
                     */
                    /*
                     mavlink_msg_optical_flow_rad_send(MAVLINK_COMM_0, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
                     integration_timespan, accumulated_flow_x, accumulated_flow_y,
                     last_vel_x, last_vel_y, accumulated_gyro_z,
                     gyro_temp, accumulated_quality/accumulated_framecount,
                     time_since_last_sonar_update,ground_distance);
                     */
                    
                    
                    /* send approximate local position estimate without heading */
                    if (global_data.param[PARAM_SYSTEM_SEND_LPOS])
                    {
                        /* rough local position estimate for unit testing */
                        lpos.x += ground_distance*accumulated_flow_x;
                        lpos.y += ground_distance*accumulated_flow_y;
                        lpos.z = -ground_distance;
                        /* velocity not directly measured and not important for testing */
                        lpos.vx = 0;
                        lpos.vy = 0;
                        lpos.vz = 0;
                        
                    } else {
                        /* toggling param allows user reset */
                        lpos.x = 0;
                        lpos.y = 0;
                        lpos.z = 0;
                        lpos.vx = 0;
                        lpos.vy = 0;
                        lpos.vz = 0;
                    }
                    
                    if (global_data.param[PARAM_USB_SEND_FLOW])
                    {
                        mavlink_msg_optical_flow_send(MAVLINK_COMM_2, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
                                                      pixel_flow_x_sum * 10.0f, pixel_flow_y_sum * 10.0f,
                                                      flow_comp_m_x, flow_comp_m_y, qual, ground_distance);
                        
                        
                        mavlink_msg_optical_flow_rad_send(MAVLINK_COMM_2, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
                                                          integration_timespan, accumulated_flow_x, accumulated_flow_y,
                                                          accumulated_gyro_x, accumulated_gyro_y, accumulated_gyro_z,
                                                          gyro_temp, accumulated_quality/accumulated_framecount,
                                                          time_since_last_sonar_update,ground_distance);
                    }
                    
                    
                    if(global_data.param[PARAM_USB_SEND_GYRO])
                    {
                        mavlink_msg_debug_vect_send(MAVLINK_COMM_2, "GYRO", get_boot_time_us(), x_rate, y_rate, z_rate);
                    }
                    
                    integration_timespan = 0;
                    accumulated_flow_x = 0;
                    accumulated_flow_y = 0;
                    accumulated_framecount = 0;
                    accumulated_quality = 0;
                    accumulated_gyro_x = 0;
                    accumulated_gyro_y = 0;
                    accumulated_gyro_z = 0;
                    
                    velocity_x_sum = 0.0f;
                    velocity_y_sum = 0.0f;
                    pixel_flow_x_sum = 0.0f;
                    pixel_flow_y_sum = 0.0f;
                    valid_frame_count = 0;
                    pixel_flow_count = 0;
                }
            }
            
            /* forward flow from other sensors */
            if (counter % 2)
            {
                communication_receive_forward();
            }
            
            /* send system state, receive commands */
            if (send_system_state_now)
            {
                /* every second */
                if (global_data.param[PARAM_SYSTEM_SEND_STATE])
                {
                    communication_system_state_send();
                }
                send_system_state_now = false;
            }
            
            /* receive commands */
            if (receive_now)
            {
                /* test every second */
                communication_receive();
                communication_receive_usb();
                receive_now = false;
            }
            
            /* sending debug msgs and requested parameters */
            if (send_params_now)
            {
                debug_message_send_one();
                communication_parameter_send();
                send_params_now = false;
            }
            
            /* send local position estimate, for testing only, doesn't account for heading */
            if (send_lpos_now)
            {
                if (global_data.param[PARAM_SYSTEM_SEND_LPOS])
                {
                    mavlink_msg_local_position_ned_send(MAVLINK_COMM_2, timer_ms, lpos.x, lpos.y, lpos.z, lpos.vx, lpos.vy, lpos.vz);
                }
                send_lpos_now = false;
            }
            
            /*  transmit raw 8-bit image */
            if (global_data.param[PARAM_USB_SEND_VIDEO] && send_image_now)
            {
                /* get size of image to send */
                uint16_t image_size_send;
                uint16_t image_width_send;
                uint16_t image_height_send;
                
                image_size_send = image_size;
                image_width_send = global_data.param[PARAM_IMAGE_WIDTH];
                image_height_send = global_data.param[PARAM_IMAGE_HEIGHT];
                
                mavlink_msg_data_transmission_handshake_send(
                                                             MAVLINK_COMM_2,
                                                             MAVLINK_DATA_STREAM_IMG_RAW8U,
                                                             image_size_send,
                                                             image_width_send,
                                                             image_height_send,
                                                             image_size_send / MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN + 1,
                                                             MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN,
                                                             100);
                LEDToggle(LED_COM);
                uint16_t frame = 0;
                for (frame = 0; frame < image_size_send / MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN + 1; frame++)
                {
                    mavlink_msg_encapsulated_data_send(MAVLINK_COMM_2, frame, &((uint8_t *) current_image)[frame * MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN]);
                }
                
                send_image_now = false;
            }
            else if (!global_data.param[PARAM_USB_SEND_VIDEO])
            {
                LEDOff(LED_COM);
            }
        }
    
        
        //EndChange
	}
}
Ejemplo n.º 12
0
void handle_mavlink_message(mavlink_channel_t chan,
		mavlink_message_t* msg)
{
	/* all messages from usart2 are directly forwarded */
	if(chan == MAVLINK_COMM_1)
	{
		uint8_t buf[MAVLINK_MAX_PACKET_LEN];
		uint32_t len;

		// Copy to USART 3
		len = mavlink_msg_to_send_buffer(buf, msg);
		mavlink_send_uart_bytes(MAVLINK_COMM_0, buf, len);

		if(global_data.param[PARAM_USB_SEND_FORWARD])
			mavlink_send_uart_bytes(MAVLINK_COMM_2, buf, len);

		return;
	}

	/* forwarded received messages from usb and usart3 to usart2 */
	uint8_t buf[MAVLINK_MAX_PACKET_LEN];
	uint32_t len;

	/* copy to usart2 */
	len = mavlink_msg_to_send_buffer(buf, msg);
	for (int i = 0; i < len; i++)
	{
		usart2_tx_ringbuffer_push(buf, len);
	}

	/* handling messages */
	switch (msg->msgid)
	{
		case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
		{
			mavlink_param_request_read_t set;
			mavlink_msg_param_request_read_decode(msg, &set);

			/* Check if this message is for this system */
			if ((uint8_t) set.target_system
					== (uint8_t) global_data.param[PARAM_SYSTEM_ID]
												   && (uint8_t) set.target_component
												   == (uint8_t) global_data.param[PARAM_COMPONENT_ID])
			{
				char* key = (char*) set.param_id;

				if (set.param_id[0] != -1)
				{
					/* Choose parameter based on index */
					if ((set.param_index >= 0) && (set.param_index < ONBOARD_PARAM_COUNT))
					{
						/* Report back value */
						mavlink_msg_param_value_send(chan,
								global_data.param_name[set.param_index],
								global_data.param[set.param_index], MAVLINK_TYPE_FLOAT, ONBOARD_PARAM_COUNT, set.param_index);
					}
				}
				else
				{
					for (int i = 0; i < ONBOARD_PARAM_COUNT; i++)
					{
						bool match = true;
						for (int j = 0; j < ONBOARD_PARAM_NAME_LENGTH; j++)
						{
							/* Compare */
							if (((char) (global_data.param_name[i][j]))
									!= (char) (key[j]))
							{
								match = false;
							}

							/* End matching if null termination is reached */
							if (((char) global_data.param_name[i][j]) == '\0')
							{
								break;
							}
						}

						/* Check if matched */
						if (match)
						{
							/* Report back value */
							mavlink_msg_param_value_send(chan,
									global_data.param_name[i],
									global_data.param[i], MAVLINK_TYPE_FLOAT, ONBOARD_PARAM_COUNT, i);
						}
					}
				}
			}
		}
		break;
		case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
		{
			/* Start sending parameters */
			m_parameter_i = 0;
		}
		break;
		case MAVLINK_MSG_ID_PARAM_SET:
		{
			mavlink_param_set_t set;
			mavlink_msg_param_set_decode(msg, &set);

			/* Check if this message is for this system */
			if ((uint8_t) set.target_system
					== (uint8_t) global_data.param[PARAM_SYSTEM_ID]
												   && (uint8_t) set.target_component
												   == (uint8_t) global_data.param[PARAM_COMPONENT_ID])
			{
				char* key = (char*) set.param_id;

				for (int i = 0; i < ONBOARD_PARAM_COUNT; i++)
				{
					bool match = true;
					for (int j = 0; j < ONBOARD_PARAM_NAME_LENGTH; j++)
					{
						/* Compare */
						if (((char) (global_data.param_name[i][j]))
								!= (char) (key[j]))
						{
							match = false;
						}

						/* End matching if null termination is reached */
						if (((char) global_data.param_name[i][j]) == '\0')
						{
							break;
						}
					}

					/* Check if matched */
					if (match)
					{
						/* Only write and emit changes if there is actually a difference
						 * AND only write if new value is NOT "not-a-number"
						 * AND is NOT infinity
						 */
						if (global_data.param[i] != set.param_value
								&& !isnan(set.param_value)
								&& !isinf(set.param_value)
								&& global_data.param_access[i])
						{
							global_data.param[i] = set.param_value;

							/* handle sensor position */
							if(i == PARAM_SENSOR_POSITION)
							{
								set_sensor_position_settings((uint8_t) set.param_value);
								mt9v034_context_configuration();
								dma_reconfigure();
								buffer_reset();
							}

							/* handle low light mode and noise correction */
							else if(i == PARAM_IMAGE_LOW_LIGHT || i == PARAM_IMAGE_ROW_NOISE_CORR|| i == PARAM_IMAGE_TEST_PATTERN)
							{
								mt9v034_context_configuration();
								dma_reconfigure();
								buffer_reset();
							}

							/* handle calibration on/off */
							else if(i == PARAM_VIDEO_ONLY)
							{
								mt9v034_set_context();
								dma_reconfigure();
								buffer_reset();

								if(global_data.param[PARAM_VIDEO_ONLY])
									debug_string_message_buffer("Calibration Mode On");
								else
									debug_string_message_buffer("Calibration Mode Off");
							}

							/* handle sensor position */
							else if(i == PARAM_GYRO_SENSITIVITY_DPS)
							{
								l3gd20_config();
							}

							else
							{
								debug_int_message_buffer("Parameter received, param id =", i);
							}

							/* report back new value */
							mavlink_msg_param_value_send(MAVLINK_COMM_0,
									global_data.param_name[i],
									global_data.param[i], MAVLINK_TYPE_FLOAT, ONBOARD_PARAM_COUNT, i);
							mavlink_msg_param_value_send(MAVLINK_COMM_2,
									global_data.param_name[i],
									global_data.param[i], MAVLINK_TYPE_FLOAT, ONBOARD_PARAM_COUNT, i);

						}
						else
						{
							/* send back current value because it is not accepted or not write access*/
							mavlink_msg_param_value_send(MAVLINK_COMM_0,
									global_data.param_name[i],
									global_data.param[i], MAVLINK_TYPE_FLOAT, ONBOARD_PARAM_COUNT, i);
							mavlink_msg_param_value_send(MAVLINK_COMM_2,
									global_data.param_name[i],
									global_data.param[i], MAVLINK_TYPE_FLOAT, ONBOARD_PARAM_COUNT, i);
						}
					}
				}
			}
		}
		break;

		case MAVLINK_MSG_ID_PING:
		{
			mavlink_ping_t ping;
			mavlink_msg_ping_decode(msg, &ping);
			if (ping.target_system == 0 && ping.target_component == 0)
			{
				/* Respond to ping */
				uint64_t r_timestamp = get_boot_time_us();
				mavlink_msg_ping_send(chan, ping.seq, msg->sysid, msg->compid, r_timestamp);
			}
		}
		break;

		case MAVLINK_MSG_ID_COMMAND_LONG:
		{
			mavlink_command_long_t cmd;
			mavlink_msg_command_long_decode(msg, &cmd);

			switch (cmd.command) {
				case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
				if (((int)(cmd.param1)) == 1) {
					mavlink_msg_command_ack_send(chan, cmd.command, MAV_RESULT_ACCEPTED);
					/* reboot */
					systemreset(false);

				} else if (((int)(cmd.param1)) == 3) {
					mavlink_msg_command_ack_send(chan, cmd.command, MAV_RESULT_ACCEPTED);
					/* reboot to bootloader */
					systemreset(true);

				} else {
					/* parameters are wrong */
					mavlink_msg_command_ack_send(chan, cmd.command, MAV_RESULT_FAILED);
					// XXX add INVALID INPUT to MAV_RESULT
				}
				break;

				default:
					mavlink_msg_command_ack_send(chan, cmd.command, MAV_RESULT_UNSUPPORTED);
				break;
			}
		}
		break;

		default:
			break;
	}
}
Ejemplo n.º 13
0
bool camera_init(camera_ctx *ctx, const camera_sensor_interface *sensor, const camera_transport_interface *transport,
				 uint32_t exposure_min_clks, uint32_t exposure_max_clks, float analog_gain_max,
				 const  camera_img_param *img_param,
				 camera_image_buffer buffers[], size_t buffer_count) {
	memset(ctx, 0, sizeof(camera_ctx));
	ctx->sensor    = sensor;
	ctx->transport = transport;
	// check parameter:
	if (buffer_count > CONFIG_CAMERA_MAX_BUFFER_COUNT && buffer_count < 2) {
		return false;
	}
	uint32_t img_size = (uint32_t)img_param->size.x * (uint32_t)img_param->size.y;
	if (img_size % ctx->transport->transfer_size != 0 || img_size / ctx->transport->transfer_size < 2) {
		// invalid size parameter!
		return false;
	}
	// initialize state:
	ctx->resync_discard_frame_count = -1;
	ctx->exposure_min_clks = exposure_min_clks;
	ctx->exposure_max_clks = exposure_max_clks;
	ctx->analog_gain_max   = analog_gain_max;
	ctx->analog_gain       = 1;
	ctx->exposure          = ctx->exposure_min_clks;
	ctx->exposure_smoothing = ctx->exposure_min_clks;
	ctx->exposure_sampling_stride = 0;
	ctx->exposure_skip_frame_cnt = 0;
	memset(ctx->exposure_bins, 0, sizeof(ctx->exposure_bins));
	ctx->exposure_hist_count = 0;
	ctx->img_stream_param.p = *img_param;
	ctx->img_stream_param.analog_gain = ctx->analog_gain;
	ctx->img_stream_param.exposure = ctx->exposure;
	ctx->snapshot_param = ctx->img_stream_param;
	int i;
	for (i = 0; i < buffer_count; ++i) {
		// check the buffer:
		if (buffers[i].buffer_size < img_size || buffers[i].buffer == NULL) {
			return false;
		}
		// init the buffer:
		ctx->buffers[i] = buffers[i];
		ctx->buffers[i].frame_number = 0;
		ctx->buffers[i].timestamp = get_boot_time_us();
		ctx->buffers[i].param = ctx->img_stream_param;
		memset(ctx->buffers[i].buffer, 0, img_size);
		// init the avail_bufs array:
		ctx->buf_avail[i] = i;
	}
	ctx->buffer_count    = buffer_count;
	ctx->buf_avail_count = buffer_count;
	ctx->new_frame_arrived = false;
	
	ctx->snapshot_buffer = NULL;
	
	ctx->frame_done_infront_count = 0;
	
	ctx->cur_frame_number = buffer_count + 1;
	ctx->seq_frame_receiving = false;
	ctx->cur_frame_target_buf   = NULL;
	
	ctx->seq_snapshot_active                 = false;
	ctx->seq_pend_img_stream_param        = false;
	// initialize hardware:
	if (!ctx->transport->init(ctx->transport->usr,
							  camera_transport_transfer_done_fn,
							  camera_transport_frame_done_fn,
							  ctx)) {
		return false;
	}
	if (!ctx->sensor->init(ctx->sensor->usr, &ctx->img_stream_param)) {
		return false;
	}
	/* after initialization start the discard count down! */
	ctx->resync_discard_frame_count = 16;
	return true;
}
Ejemplo n.º 14
0
Archivo: main.c Proyecto: PX4/Flow
/**
  * @brief  Main function.
  */
int main(void)
{
	__enable_irq();

	/* load settings and parameters */
	global_data_reset_param_defaults();
	global_data_reset();
	PROBE_INIT();
	/* init led */
	LEDInit(LED_ACT);
	LEDInit(LED_COM);
	LEDInit(LED_ERR);
	LEDOff(LED_ACT);
	LEDOff(LED_COM);
	LEDOff(LED_ERR);
        board_led_rgb(255,255,255, 1);
        board_led_rgb(  0,  0,255, 0);
        board_led_rgb(  0,  0, 0, 0);
        board_led_rgb(255,  0,  0, 1);
        board_led_rgb(255,  0,  0, 2);
        board_led_rgb(255,  0,  0, 3);
                board_led_rgb(  0,255,  0, 3);
        board_led_rgb(  0,  0,255, 4);

	/* enable FPU on Cortex-M4F core */
	SCB_CPACR |= ((3UL << 10 * 2) | (3UL << 11 * 2)); /* set CP10 Full Access and set CP11 Full Access */

	/* init clock */
	if (SysTick_Config(SystemCoreClock / 100000))/*set timer to trigger interrupt every 10 microsecond */
	{
		/* capture clock error */
		LEDOn(LED_ERR);
		while (1);
	}

	/* init usb */
	USBD_Init(	&USB_OTG_dev,
				USB_OTG_FS_CORE_ID,
				&USR_desc,
				&USBD_CDC_cb,
				&USR_cb);

	/* init mavlink */
	communication_init();

	/* enable image capturing */
	enable_image_capture();

	/* gyro config */
	gyro_config();

	/* init and clear fast image buffers */
	for (int i = 0; i < global_data.param[PARAM_IMAGE_WIDTH] * global_data.param[PARAM_IMAGE_HEIGHT]; i++)
	{
		image_buffer_8bit_1[i] = 0;
		image_buffer_8bit_2[i] = 0;
	}

	uint8_t * current_image = image_buffer_8bit_1;
	uint8_t * previous_image = image_buffer_8bit_2;

	/* usart config*/
	usart_init();

    /* i2c config*/
    i2c_init();

	/* sonar config*/
	float sonar_distance_filtered = 0.0f; // distance in meter
	float sonar_distance_raw = 0.0f; // distance in meter
	bool distance_valid = false;
	sonar_config();

	/* reset/start timers */
	timer[TIMER_SONAR] = SONAR_TIMER_COUNT;
	timer[TIMER_SYSTEM_STATE] = SYSTEM_STATE_COUNT;
	timer[TIMER_RECEIVE] = SYSTEM_STATE_COUNT / 2;
	timer[TIMER_PARAMS] = PARAMS_COUNT;
	timer[TIMER_IMAGE] = global_data.param[PARAM_VIDEO_RATE];

	/* variables */
	uint32_t counter = 0;
	uint8_t qual = 0;

	/* bottom flow variables */
	float pixel_flow_x = 0.0f;
	float pixel_flow_y = 0.0f;
	float pixel_flow_x_sum = 0.0f;
	float pixel_flow_y_sum = 0.0f;
	float velocity_x_sum = 0.0f;
	float velocity_y_sum = 0.0f;
	float velocity_x_lp = 0.0f;
	float velocity_y_lp = 0.0f;
	int valid_frame_count = 0;
	int pixel_flow_count = 0;

	static float accumulated_flow_x = 0;
	static float accumulated_flow_y = 0;
	static float accumulated_gyro_x = 0;
	static float accumulated_gyro_y = 0;
	static float accumulated_gyro_z = 0;
	static uint16_t accumulated_framecount = 0;
	static uint16_t accumulated_quality = 0;
	static uint32_t integration_timespan = 0;
	static uint32_t lasttime = 0;
	uint32_t time_since_last_sonar_update= 0;
	uint32_t time_last_pub= 0;

	uavcan_start();
	/* main loop */
	while (1)
	{
                PROBE_1(false);
                uavcan_run();
                PROBE_1(true);
		/* reset flow buffers if needed */
		if(buffer_reset_needed)
		{
			buffer_reset_needed = 0;
			for (int i = 0; i < global_data.param[PARAM_IMAGE_WIDTH] * global_data.param[PARAM_IMAGE_HEIGHT]; i++)
			{
				image_buffer_8bit_1[i] = 0;
				image_buffer_8bit_2[i] = 0;
			}
			delay(500);
			continue;
		}

		/* calibration routine */
		if(FLOAT_AS_BOOL(global_data.param[PARAM_VIDEO_ONLY]))
		{
			while(FLOAT_AS_BOOL(global_data.param[PARAM_VIDEO_ONLY]))
			{
				dcmi_restart_calibration_routine();

				/* waiting for first quarter of image */
				while(get_frame_counter() < 2){}
				dma_copy_image_buffers(&current_image, &previous_image, FULL_IMAGE_SIZE, 1);

				/* waiting for second quarter of image */
				while(get_frame_counter() < 3){}
				dma_copy_image_buffers(&current_image, &previous_image, FULL_IMAGE_SIZE, 1);

				/* waiting for all image parts */
				while(get_frame_counter() < 4){}

				send_calibration_image(&previous_image, &current_image);

				if (FLOAT_AS_BOOL(global_data.param[PARAM_SYSTEM_SEND_STATE]))
					communication_system_state_send();

				communication_receive_usb();
				debug_message_send_one();
				communication_parameter_send();

				LEDToggle(LED_COM);
			}

			dcmi_restart_calibration_routine();
			LEDOff(LED_COM);
		}

		uint16_t image_size = global_data.param[PARAM_IMAGE_WIDTH] * global_data.param[PARAM_IMAGE_HEIGHT];

		/* new gyroscope data */
		float x_rate_sensor, y_rate_sensor, z_rate_sensor;
		int16_t gyro_temp;
		gyro_read(&x_rate_sensor, &y_rate_sensor, &z_rate_sensor,&gyro_temp);

		/* gyroscope coordinate transformation */
		float x_rate = y_rate_sensor; // change x and y rates
		float y_rate = - x_rate_sensor;
		float z_rate = z_rate_sensor; // z is correct

		/* calculate focal_length in pixel */
		const float focal_length_px = (global_data.param[PARAM_FOCAL_LENGTH_MM]) / (4.0f * 6.0f) * 1000.0f; //original focal lenght: 12mm pixelsize: 6um, binning 4 enabled

		/* get sonar data */
		distance_valid = sonar_read(&sonar_distance_filtered, &sonar_distance_raw);

		/* reset to zero for invalid distances */
		if (!distance_valid) {
			sonar_distance_filtered = 0.0f;
			sonar_distance_raw = 0.0f;
		}

		/* compute optical flow */
		if (FLOAT_EQ_INT(global_data.param[PARAM_SENSOR_POSITION], BOTTOM))
		{
			/* copy recent image to faster ram */
			dma_copy_image_buffers(&current_image, &previous_image, image_size, 1);

			/* compute optical flow */
			qual = compute_flow(previous_image, current_image, x_rate, y_rate, z_rate, &pixel_flow_x, &pixel_flow_y);

			/*
			 * real point P (X,Y,Z), image plane projection p (x,y,z), focal-length f, distance-to-scene Z
			 * x / f = X / Z
			 * y / f = Y / Z
			 */
			float flow_compx = pixel_flow_x / focal_length_px / (get_time_between_images() / 1000000.0f);
			float flow_compy = pixel_flow_y / focal_length_px / (get_time_between_images() / 1000000.0f);

			if (qual > 0)
			{
				valid_frame_count++;

				uint32_t deltatime = (get_boot_time_us() - lasttime);
				integration_timespan += deltatime;
				accumulated_flow_x += pixel_flow_y  / focal_length_px * 1.0f; //rad axis swapped to align x flow around y axis
				accumulated_flow_y += pixel_flow_x  / focal_length_px * -1.0f;//rad
				accumulated_gyro_x += x_rate * deltatime / 1000000.0f;	//rad
				accumulated_gyro_y += y_rate * deltatime / 1000000.0f;	//rad
				accumulated_gyro_z += z_rate * deltatime / 1000000.0f;	//rad
				accumulated_framecount++;
				accumulated_quality += qual;
			}


			/* integrate velocity and output values only if distance is valid */
			if (distance_valid)
			{
				/* calc velocity (negative of flow values scaled with distance) */
				float new_velocity_x = - flow_compx * sonar_distance_filtered;
				float new_velocity_y = - flow_compy * sonar_distance_filtered;

				time_since_last_sonar_update = (get_boot_time_us()- get_sonar_measure_time());

				if (qual > 0)
				{
					velocity_x_sum += new_velocity_x;
					velocity_y_sum += new_velocity_y;

					/* lowpass velocity output */
					velocity_x_lp = global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW] * new_velocity_x +
							(1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * velocity_x_lp;
					velocity_y_lp = global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW] * new_velocity_y +
							(1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * velocity_y_lp;
				}
				else
				{
					/* taking flow as zero */
					velocity_x_lp = (1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * velocity_x_lp;
					velocity_y_lp = (1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * velocity_y_lp;
				}
			}
			else
			{
				/* taking flow as zero */
				velocity_x_lp = (1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * velocity_x_lp;
				velocity_y_lp = (1.0f - global_data.param[PARAM_BOTTOM_FLOW_WEIGHT_NEW]) * velocity_y_lp;
			}
			//update lasttime
			lasttime = get_boot_time_us();

			pixel_flow_x_sum += pixel_flow_x;
			pixel_flow_y_sum += pixel_flow_y;
			pixel_flow_count++;

		}

		counter++;

		if (FLOAT_EQ_INT(global_data.param[PARAM_SENSOR_POSITION], BOTTOM))
		{
			/* send bottom flow if activated */

			float ground_distance = 0.0f;


			if(FLOAT_AS_BOOL(global_data.param[PARAM_SONAR_FILTERED]))
			{
				ground_distance = sonar_distance_filtered;
			}
			else
			{
				ground_distance = sonar_distance_raw;
			}

                        uavcan_define_export(i2c_data, legacy_12c_data_t, ccm);
                        uavcan_define_export(range_data, range_data_t, ccm);
			uavcan_timestamp_export(i2c_data);
                        uavcan_assign(range_data.time_stamp_utc, i2c_data.time_stamp_utc);
			//update I2C transmitbuffer
			if(valid_frame_count>0)
			{
				update_TX_buffer(pixel_flow_x, pixel_flow_y, velocity_x_sum/valid_frame_count, velocity_y_sum/valid_frame_count, qual,
						ground_distance, x_rate, y_rate, z_rate, gyro_temp, uavcan_use_export(i2c_data));
			}
			else
			{
				update_TX_buffer(pixel_flow_x, pixel_flow_y, 0.0f, 0.0f, qual,
						ground_distance, x_rate, y_rate, z_rate, gyro_temp, uavcan_use_export(i2c_data));
			}
	                PROBE_2(false);
                        uavcan_publish(range, 40, range_data);
	                PROBE_2(true);

                        PROBE_3(false);
                        uavcan_publish(flow, 40, i2c_data);
                        PROBE_3(true);

            //serial mavlink  + usb mavlink output throttled
			uint32_t now = get_boot_time_us();
			uint32_t time_since_last_pub = now - time_last_pub;
			if (time_since_last_pub > (1.0e6f/global_data.param[PARAM_BOTTOM_FLOW_PUB_RATE]))
			{
				time_last_pub = now;

				float flow_comp_m_x = 0.0f;
				float flow_comp_m_y = 0.0f;

				if(FLOAT_AS_BOOL(global_data.param[PARAM_BOTTOM_FLOW_LP_FILTERED]))
				{
					flow_comp_m_x = velocity_x_lp;
					flow_comp_m_y = velocity_y_lp;
				}
				else
				{
					if(valid_frame_count>0)
					{
						flow_comp_m_x = velocity_x_sum/valid_frame_count;
						flow_comp_m_y = velocity_y_sum/valid_frame_count;
					}
					else
					{
						flow_comp_m_x = 0.0f;
						flow_comp_m_y = 0.0f;
					}
				}


				// send flow
				mavlink_msg_optical_flow_send(MAVLINK_COMM_0, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
						pixel_flow_x_sum * 10.0f, pixel_flow_y_sum * 10.0f,
						flow_comp_m_x, flow_comp_m_y, qual, ground_distance);

				mavlink_msg_optical_flow_rad_send(MAVLINK_COMM_0, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
						integration_timespan, accumulated_flow_x, accumulated_flow_y,
						accumulated_gyro_x, accumulated_gyro_y, accumulated_gyro_z,
						gyro_temp, accumulated_quality/accumulated_framecount,
						time_since_last_sonar_update,ground_distance);

				/* send approximate local position estimate without heading */
				if (FLOAT_AS_BOOL(global_data.param[PARAM_SYSTEM_SEND_LPOS]))
				{
					/* rough local position estimate for unit testing */
					lpos.x += ground_distance*accumulated_flow_x;
					lpos.y += ground_distance*accumulated_flow_y;
					lpos.z = -ground_distance;
					lpos.vx = ground_distance*accumulated_flow_x/integration_timespan;
					lpos.vy = ground_distance*accumulated_flow_y/integration_timespan;
					lpos.vz = 0; // no direct measurement, just ignore

				} else {
					/* toggling param allows user reset */
					lpos.x = 0;
					lpos.y = 0;
					lpos.z = 0;
					lpos.vx = 0;
					lpos.vy = 0;
					lpos.vz = 0;
				}

				if (FLOAT_AS_BOOL(global_data.param[PARAM_USB_SEND_FLOW]))
				{
					mavlink_msg_optical_flow_send(MAVLINK_COMM_2, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
							pixel_flow_x_sum * 10.0f, pixel_flow_y_sum * 10.0f,
						flow_comp_m_x, flow_comp_m_y, qual, ground_distance);


					mavlink_msg_optical_flow_rad_send(MAVLINK_COMM_2, get_boot_time_us(), global_data.param[PARAM_SENSOR_ID],
							integration_timespan, accumulated_flow_x, accumulated_flow_y,
							accumulated_gyro_x, accumulated_gyro_y, accumulated_gyro_z,
							gyro_temp, accumulated_quality/accumulated_framecount,
							time_since_last_sonar_update,ground_distance);
				}


				if(FLOAT_AS_BOOL(global_data.param[PARAM_USB_SEND_GYRO]))
				{
					mavlink_msg_debug_vect_send(MAVLINK_COMM_2, "GYRO", get_boot_time_us(), x_rate, y_rate, z_rate);
				}

				integration_timespan = 0;
				accumulated_flow_x = 0;
				accumulated_flow_y = 0;
				accumulated_framecount = 0;
				accumulated_quality = 0;
				accumulated_gyro_x = 0;
				accumulated_gyro_y = 0;
				accumulated_gyro_z = 0;

				velocity_x_sum = 0.0f;
				velocity_y_sum = 0.0f;
				pixel_flow_x_sum = 0.0f;
				pixel_flow_y_sum = 0.0f;
				valid_frame_count = 0;
				pixel_flow_count = 0;
			}
		}

		/* forward flow from other sensors */
		if (counter % 2)
		{
			communication_receive_forward();
		}

		/* send system state, receive commands */
		if (send_system_state_now)
		{
			/* every second */
			if (FLOAT_AS_BOOL(global_data.param[PARAM_SYSTEM_SEND_STATE]))
			{
				communication_system_state_send();
			}
			send_system_state_now = false;
		}

		/* receive commands */
		if (receive_now)
		{
			/* test every second */
			communication_receive();
			communication_receive_usb();
			receive_now = false;
		}

		/* sending debug msgs and requested parameters */
		if (send_params_now)
		{
			debug_message_send_one();
			communication_parameter_send();
			send_params_now = false;
		}

		/* send local position estimate, for testing only, doesn't account for heading */
		if (send_lpos_now)
		{
			if (FLOAT_AS_BOOL(global_data.param[PARAM_SYSTEM_SEND_LPOS]))
			{
				mavlink_msg_local_position_ned_send(MAVLINK_COMM_2, timer_ms, lpos.x, lpos.y, lpos.z, lpos.vx, lpos.vy, lpos.vz);
			}
			send_lpos_now = false;
		}

		/*  transmit raw 8-bit image */
		if (FLOAT_AS_BOOL(global_data.param[PARAM_USB_SEND_VIDEO])&& send_image_now)
		{
			/* get size of image to send */
			uint16_t image_size_send;
			uint16_t image_width_send;
			uint16_t image_height_send;

			image_size_send = image_size;
			image_width_send = global_data.param[PARAM_IMAGE_WIDTH];
			image_height_send = global_data.param[PARAM_IMAGE_HEIGHT];

			mavlink_msg_data_transmission_handshake_send(
					MAVLINK_COMM_2,
					MAVLINK_DATA_STREAM_IMG_RAW8U,
					image_size_send,
					image_width_send,
					image_height_send,
					image_size_send / MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN + 1,
					MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN,
					100);
			LEDToggle(LED_COM);
			uint16_t frame = 0;
			for (frame = 0; frame < image_size_send / MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN + 1; frame++)
			{
				mavlink_msg_encapsulated_data_send(MAVLINK_COMM_2, frame, &((uint8_t *) previous_image)[frame * MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN]);
			}

			send_image_now = false;
		}
		else if (!FLOAT_AS_BOOL(global_data.param[PARAM_USB_SEND_VIDEO]))
		{
			LEDOff(LED_COM);
		}
	}
}