Beispiel #1
0
void
MavlinkReceiver::handle_message_set_mode(mavlink_message_t *msg)
{
	mavlink_set_mode_t new_mode;
	mavlink_msg_set_mode_decode(msg, &new_mode);

	struct vehicle_command_s vcmd;
	memset(&vcmd, 0, sizeof(vcmd));

	union px4_custom_mode custom_mode;
	custom_mode.data = new_mode.custom_mode;
	/* copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
	vcmd.param1 = new_mode.base_mode;
	vcmd.param2 = custom_mode.main_mode;
	vcmd.param3 = 0;
	vcmd.param4 = 0;
	vcmd.param5 = 0;
	vcmd.param6 = 0;
	vcmd.param7 = 0;
	vcmd.command = VEHICLE_CMD_DO_SET_MODE;
	vcmd.target_system = new_mode.target_system;
	vcmd.target_component = MAV_COMP_ID_ALL;
	vcmd.source_system = msg->sysid;
	vcmd.source_component = msg->compid;
	vcmd.confirmation = 1;

	if (_cmd_pub < 0) {
		_cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);

	} else {
		orb_publish(ORB_ID(vehicle_command), _cmd_pub, &vcmd);
	}
}
Beispiel #2
0
/* определяет, кому пришло это сообщение и кидает в соотверствующий почтовый ящик */
bool_t sort_input_messages(mavlink_message_t *msg){
  msg_t status = RDY_OK;

  switch(msg->msgid){
    SORTINCASE(param_request_list, PARAM_REQUEST_LIST,  param_set)
    SORTINCASE(param_request_read, PARAM_REQUEST_READ,  param_set)
    SORTINCASE(param_set, PARAM_SET,                    param_set)

    SORTINCASE(command_long, COMMAND_LONG,              command_long)





  case MAVLINK_MSG_ID_SET_MODE:
    mavlink_msg_set_mode_decode(msg, &mavlink_set_mode_struct);
    if (mavlink_set_mode_struct.target_system == mavlink_system_struct.sysid)
      mavlink_system_struct.mode = mavlink_set_mode_struct.custom_mode | mavlink_set_mode_struct.base_mode;
    break;

  case MAVLINK_MSG_ID_HEARTBEAT:
    break;
  default:
    //Do nothing
    break;
  }

  return LINK_SUCCESS;
}
Beispiel #3
0
/*
  handle a SET_MODE MAVLink message
 */
void GCS_MAVLINK::handle_set_mode(mavlink_message_t* msg, bool (*set_mode)(uint8_t mode))
{
    uint8_t result = MAV_RESULT_FAILED;
    mavlink_set_mode_t packet;
    mavlink_msg_set_mode_decode(msg, &packet);

    // only accept custom modes because there is no easy mapping from Mavlink flight modes to AC flight modes
    if (packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
        if (set_mode(packet.custom_mode)) {
            result = MAV_RESULT_ACCEPTED;
        }
    } else if (packet.base_mode == MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
        // set the safety switch position. Must be in a command by itself
        if (packet.custom_mode == 0) {
            // turn safety off (pwm outputs flow to the motors)
            hal.rcout->force_safety_off();
            result = MAV_RESULT_ACCEPTED;
        } else if (packet.custom_mode == 1) {
            // turn safety on (no pwm outputs to the motors)
            if (hal.rcout->force_safety_on()) {
                result = MAV_RESULT_ACCEPTED;
            }
        }
    }

    // send ACK or NAK
    mavlink_msg_command_ack_send_buf(msg, chan, MAVLINK_MSG_ID_SET_MODE, result);
}
Beispiel #4
0
void GCS_Mavlink<T>::handle_set_mode(mavlink_message_t *msg)
{
	mavlink_set_mode_t set_mode_t;
	mavlink_msg_set_mode_decode(msg, &set_mode_t);
	if (set_mode_t.target_system == _systemId)
	{
		switch (set_mode_t.base_mode) {
			case MAV_MODE_STABILIZE_ARMED: {
				_mav_state = MAV_STATE_ACTIVE;
				_mav_mode_flag |= MAV_MODE_FLAG_SAFETY_ARMED;
				_mav_mode = (MAV_MODE) set_mode_t.base_mode;
				motorsQuad.set_armed(ARM);
				leds.set_state(R, ON);
				break;
			}
			case MAV_MODE_STABILIZE_DISARMED: {
				_mav_state = MAV_STATE_STANDBY;
				_mav_mode_flag &= ~MAV_MODE_FLAG_SAFETY_ARMED;
				_mav_mode = (MAV_MODE) set_mode_t.base_mode;
				motorsQuad.set_armed(DISARM);
				leds.set_state(R, OFF);

				break;
			}
			case MAV_MODE_MANUAL_DISARMED: {
				_mav_state = MAV_STATE_STANDBY;
				_mav_mode_flag &= ~MAV_MODE_FLAG_SAFETY_ARMED;
				_mav_mode = (MAV_MODE) set_mode_t.base_mode;
				motorsQuad.set_armed(DISARM);
				leds.set_state(R, OFF);
				break;
			}
			case MAV_MODE_MANUAL_ARMED: {
				_mav_state = MAV_STATE_ACTIVE;
				_mav_mode_flag |= MAV_MODE_FLAG_SAFETY_ARMED;
				_mav_mode = (MAV_MODE) set_mode_t.base_mode;
				motorsQuad.set_armed(ARM);
				leds.set_state(R, ON);
				break;
			}
			default: {
				_mav_mode = (MAV_MODE) set_mode_t.base_mode;
				break;
			}
		}

//		Serial.println(mav_mode);
		send_hearthbeat();
	}
}
void state_telemetry_set_mav_mode(state_t* state, uint32_t sysid, mavlink_message_t* msg)
{
	mavlink_set_mode_t packet;
	
	mavlink_msg_set_mode_decode(msg,&packet);
	
	// Check if this message is for this system and subsystem
	// No component ID in mavlink_set_mode_t so no control
	if ((uint8_t)packet.target_system == (uint8_t)sysid)
	{
		print_util_dbg_print("base_mode:");
		print_util_dbg_print_num(packet.base_mode,10);
		print_util_dbg_print(", custom mode:");
		print_util_dbg_print_num(packet.custom_mode,10);
		print_util_dbg_print("\r\n");

		mav_mode_t new_mode;
		new_mode.byte = packet.base_mode;
		
		if (new_mode.ARMED == ARMED_ON)
		{
			if (state->mav_mode.ARMED == ARMED_OFF)
			{
				state_switch_to_active_mode(state, &state->mav_state);
			}
		}
		else
		{
			state->mav_state = MAV_STATE_STANDBY;
		}
		
		state->mav_mode.ARMED = new_mode.ARMED;
		state->mav_mode.MANUAL = new_mode.MANUAL;
		//state->mav_mode.HIL = new_mode.HIL;
		state->mav_mode.STABILISE = new_mode.STABILISE;
		state->mav_mode.GUIDED = new_mode.GUIDED;
		state->mav_mode.AUTO = new_mode.AUTO;
		state->mav_mode.TEST = new_mode.TEST;
		state->mav_mode.CUSTOM = new_mode.CUSTOM;
		
		//state->mav_mode_custom = packet.custom_mode;
		
		print_util_dbg_print("New mav mode:");
		print_util_dbg_print_num(state->mav_mode.byte,10);
		print_util_dbg_print("\r");
		
	}
}
Beispiel #6
0
//@{
void handle_mavlink_message(mavlink_channel_t chan,
		mavlink_message_t* msg)
{
	uint8_t buf[MAVLINK_MAX_PACKET_LEN];
	uint32_t len;
	switch (chan)
	{
	case MAVLINK_COMM_0:
	{
		if (msg->msgid != MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE)
		{
			// Copy to COMM 1
			len = mavlink_msg_to_send_buffer(buf, msg);
			for (int i = 0; i < len; i++)
			{
				uart1_transmit(buf[i]);
			}
		}
	}
	break;
	case MAVLINK_COMM_1:
	{
		if (msg->msgid != MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE && msg->msgid != MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE)
		{
			// Copy to COMM 0
			len = mavlink_msg_to_send_buffer(buf, msg);
			for (int i = 0; i < len; i++)
			{
				uart0_transmit(buf[i]);
			}
			break;
		}
	}
	default:
		break;
	}


	switch (msg->msgid)
	{
	case MAVLINK_MSG_ID_SET_MODE:
	{
		mavlink_set_mode_t mode;
		mavlink_msg_set_mode_decode(msg, &mode);
		// Check if this system should change the mode
		if (mode.target == (uint8_t)global_data.param[PARAM_SYSTEM_ID])
		{
			sys_set_mode(mode.mode);

			// Emit current mode
			mavlink_msg_sys_status_send(MAVLINK_COMM_0, global_data.state.mav_mode, global_data.state.nav_mode,
					global_data.state.status, global_data.cpu_usage, global_data.battery_voltage,
					global_data.motor_block, communication_get_uart_drop_rate());
			mavlink_msg_sys_status_send(MAVLINK_COMM_1, global_data.state.mav_mode, global_data.state.nav_mode,
					global_data.state.status, global_data.cpu_usage, global_data.battery_voltage,
					global_data.motor_block, communication_get_uart_drop_rate());

		}
	}
	break;
	case MAVLINK_MSG_ID_ACTION:
	{
		execute_action(mavlink_msg_action_get_action(msg));

		//Forwart actions from Xbee to Onboard Computer and vice versa
		if (chan == MAVLINK_COMM_1)
		{
			mavlink_send_uart(MAVLINK_COMM_0, msg);
		}
		else if (chan == MAVLINK_COMM_0)
		{
			mavlink_send_uart(MAVLINK_COMM_1, msg);
		}
	}
	break;
	case MAVLINK_MSG_ID_SYSTEM_TIME:
	{
		if (!sys_time_clock_get_unix_offset())
		{
			int64_t offset = ((int64_t) mavlink_msg_system_time_get_time_usec(
					msg)) - (int64_t) sys_time_clock_get_time_usec();
			sys_time_clock_set_unix_offset(offset);

			debug_message_buffer("UNIX offset updated");
		}
		else
		{

			//			debug_message_buffer("UNIX offset REFUSED");
		}
	}
	break;
	case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
	{
		mavlink_request_data_stream_t stream;
		mavlink_msg_request_data_stream_decode(msg, &stream);
		switch (stream.req_stream_id)
		{
		case 0: // UNIMPLEMENTED
			break;
		case 1: // RAW SENSOR DATA
			global_data.param[PARAM_SEND_SLOT_RAW_IMU] = stream.start_stop;
			break;
		case 2: // EXTENDED SYSTEM STATUS
			global_data.param[PARAM_SEND_SLOT_ATTITUDE] = stream.start_stop;
			break;
		case 3: // REMOTE CONTROL CHANNELS
			global_data.param[PARAM_SEND_SLOT_REMOTE_CONTROL] = stream.start_stop;
			break;
		case 4: // RAW CONTROLLER
			//global_data.param[PARAM_SEND_SLOT_DEBUG_5] = stream.start_stop;
			//global_data.param[PARAM_SEND_SLOT_DEBUG_3] = stream.start_stop;
			global_data.param[PARAM_SEND_SLOT_CONTROLLER_OUTPUT] = stream.start_stop;
			break;
		case 5: // SENSOR FUSION

			//LOST IN GROUDNCONTROL
			//			global_data.param[PARAM_SEND_SLOT_DEBUG_5] = stream.start_stop;
			break;
		case 6: // POSITION
			global_data.param[PARAM_SEND_SLOT_DEBUG_5] = stream.start_stop;
			break;
		case 7: // EXTRA1
			global_data.param[PARAM_SEND_SLOT_DEBUG_2] = stream.start_stop;
			break;
		case 8: // EXTRA2
			global_data.param[PARAM_SEND_SLOT_DEBUG_4] = stream.start_stop;
			break;
		case 9: // EXTRA3
			global_data.param[PARAM_SEND_SLOT_DEBUG_6] = stream.start_stop;
			break;
		default:
			// Do nothing
			break;
		}
	}
	break;
	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] == '\0')
			{
				// Choose parameter based on index
				if (set.param_index < ONBOARD_PARAM_COUNT)
				{
					// Report back value
					mavlink_msg_param_value_send(chan,
							(int8_t*) global_data.param_name[set.param_index],
							global_data.param[set.param_index], 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,
								(int8_t*) global_data.param_name[i],
								global_data.param[i], ONBOARD_PARAM_COUNT, m_parameter_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 infy
					if (global_data.param[i] != set.param_value
							&& !isnan(set.param_value)
							&& !isinf(set.param_value))
					{
						global_data.param[i] = set.param_value;
						// Report back new value
						mavlink_msg_param_value_send(MAVLINK_COMM_0,
								(int8_t*) global_data.param_name[i],
								global_data.param[i], ONBOARD_PARAM_COUNT, m_parameter_i);
						mavlink_msg_param_value_send(MAVLINK_COMM_1,
								(int8_t*) global_data.param_name[i],
								global_data.param[i], ONBOARD_PARAM_COUNT, m_parameter_i);

						debug_message_buffer_sprintf("Parameter received param id=%i",i);
					}
				}
			}
		}
	}
	break;
	case MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET:
	{
		mavlink_position_control_setpoint_set_t pos;
		mavlink_msg_position_control_setpoint_set_decode(msg, &pos);
		if (global_data.param[PARAM_POSITIONSETPOINT_ACCEPT] == 1)
		{
			//			global_data.position_setpoint.x = pos.x;
			//			global_data.position_setpoint.y = pos.y;
			//			global_data.position_setpoint.z = pos.z;
			debug_message_buffer("Position setpoint updated. OLD?\n");
		}
		else
		{
			debug_message_buffer(
					"Position setpoint recieved but not updated. OLD?\n");
		}

		// Send back a message confirming the new position
		mavlink_msg_position_control_setpoint_send(MAVLINK_COMM_0, pos.id,
				pos.x, pos.y, pos.z, pos.yaw);
		mavlink_msg_position_control_setpoint_send(MAVLINK_COMM_1, pos.id,
				pos.x, pos.y, pos.z, pos.yaw);
	}
	break;
	case MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET:
	{
		mavlink_position_control_offset_set_t set;
		mavlink_msg_position_control_offset_set_decode(msg, &set);
		//global_data.attitude_setpoint_pos_body_offset.z = set.yaw;

		//Ball Tracking
		if (global_data.param[PARAM_POSITIONSETPOINT_ACCEPT] == 1 && global_data.param[PARAM_POSITION_YAW_TRACKING]==1)
		{
			global_data.param[PARAM_POSITION_SETPOINT_YAW]
			                  = global_data.attitude.z + set.yaw;

			mavlink_msg_debug_send(global_data.param[PARAM_SEND_DEBUGCHAN], 92, set.yaw);
		}
	}
	break;
	case MAVLINK_MSG_ID_SET_CAM_SHUTTER:
	{
		// Decode the desired shutter
		mavlink_set_cam_shutter_t cam;
		mavlink_msg_set_cam_shutter_decode(msg, &cam);
		shutter_set(cam.interval, cam.exposure);
		debug_message_buffer_sprintf("set_cam_shutter. interval %i",
				cam.interval);

	}
	break;
	case MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL:
	{
		uint8_t enable = mavlink_msg_image_trigger_control_get_enable(msg);
		shutter_control(enable);
		if (enable)
		{
			debug_message_buffer("CAM: Enabling hardware trigger");
		}
		else
		{
			debug_message_buffer("CAM: Disabling hardware trigger");
		}
	}
	break;
	case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
	{
		mavlink_vision_position_estimate_t pos;
		mavlink_msg_vision_position_estimate_decode(msg, &pos);

		vision_buffer_handle_data(&pos);
		// Update validity time is done in vision buffer

	}
	break;
	case MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE:
	{
		mavlink_vicon_position_estimate_t pos;
		mavlink_msg_vicon_position_estimate_decode(msg, &pos);

		global_data.vicon_data.x = pos.x;
		global_data.vicon_data.y = pos.y;
		global_data.vicon_data.z = pos.z;
		global_data.state.vicon_new_data=1;
		// Update validity time
		global_data.vicon_last_valid = sys_time_clock_get_time_usec();
		global_data.state.vicon_ok=1;

//		//Set data from Vicon into vision filter
//		global_data.vision_data.ang.x = pos.roll;
//		global_data.vision_data.ang.y = pos.pitch;
//		global_data.vision_data.ang.z = pos.yaw;
//
//		global_data.vision_data.pos.x = pos.x;
//		global_data.vision_data.pos.y = pos.y;
//		global_data.vision_data.pos.z = pos.z;
//
//		global_data.vision_data.new_data = 1;

		if (!global_data.state.vision_ok)
		{
			//Correct YAW
			global_data.attitude.z = pos.yaw;
			//If yaw goes to infy (no idea why) set it to setpoint, next time will be better
			if (global_data.attitude.z > 18.8495559 || global_data.attitude.z
					< -18.8495559)
			{
				global_data.attitude.z = global_data.yaw_pos_setpoint;
				debug_message_buffer(
						"vicon CRITICAL FAULT yaw was bigger than 6 PI! prevented crash");
			}
		}


		//send the vicon message to UART0 with new timestamp
		mavlink_msg_vicon_position_estimate_send(MAVLINK_COMM_0, global_data.vicon_last_valid, pos.x, pos.y, pos.z, pos.roll, pos.pitch, pos.yaw);

	}
	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 = sys_time_clock_get_unix_time();
			mavlink_msg_ping_send(chan, ping.seq, msg->sysid, msg->compid, r_timestamp);
		}
	}
	break;
	case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
	{
		mavlink_local_position_setpoint_set_t sp;
		mavlink_msg_local_position_setpoint_set_decode(msg, &sp);
		if (sp.target_system == global_data.param[PARAM_SYSTEM_ID])
		{
			if (global_data.param[PARAM_POSITIONSETPOINT_ACCEPT] == 1)
			{
				if (sp.x >= global_data.position_setpoint_min.x && sp.y
						>= global_data.position_setpoint_min.y && sp.z
						>= global_data.position_setpoint_min.z && sp.x
						<= global_data.position_setpoint_max.x && sp.y
						<= global_data.position_setpoint_max.y && sp.z
						<= global_data.position_setpoint_max.z)
				{
					debug_message_buffer("Setpoint accepted and set.");
					global_data.param[PARAM_POSITION_SETPOINT_X] = sp.x;
					global_data.param[PARAM_POSITION_SETPOINT_Y] = sp.y;
					global_data.param[PARAM_POSITION_SETPOINT_Z] = sp.z;

					if (global_data.param[PARAM_POSITION_YAW_TRACKING] == 0)
					{
						// Only update yaw if we are not tracking ball.
						global_data.param[PARAM_POSITION_SETPOINT_YAW] = sp.yaw;
					}

					//check if we want to start or land
					if (global_data.state.status == MAV_STATE_ACTIVE
							|| global_data.state.status == MAV_STATE_CRITICAL)
					{
						if (sp.z > -0.1)
						{
							if (!(global_data.state.fly == FLY_GROUNDED
									|| global_data.state.fly == FLY_SINKING
									|| global_data.state.fly
											== FLY_WAIT_LANDING
									|| global_data.state.fly == FLY_LANDING
									|| global_data.state.fly == FLY_RAMP_DOWN))
							{
								//if setpoint is lower that ground iate landing
								global_data.state.fly = FLY_SINKING;
								global_data.param[PARAM_POSITION_SETPOINT_Z]
										= -0.2;//with lowpass
								debug_message_buffer(
										"Sinking for LANDING. (z-sp lower than 10cm)");
							}
							else if (!(global_data.state.fly == FLY_GROUNDED))
							{
								global_data.param[PARAM_POSITION_SETPOINT_Z]
										= -0.2;//with lowpass
							}
						}
						else if (global_data.state.fly == FLY_GROUNDED && sp.z
								< -0.50)
						{
							//start if we were grounded and get a sp over 0.5m
							global_data.state.fly = FLY_WAIT_MOTORS;
							debug_message_buffer(
									"STARTING wait motors. (z-sp higher than 50cm)");
							//set point changed with lowpass, after 5s it will be ok.
						}
					}

					//SINK TO 0.7m if we are critical or emergency
					if (global_data.state.status == MAV_STATE_EMERGENCY
							|| global_data.state.status == MAV_STATE_CRITICAL)
					{
						global_data.param[PARAM_POSITION_SETPOINT_Z] = -0.7;//with lowpass
					}
				}
				else
				{
					debug_message_buffer("Setpoint refused. Out of range.");
				}
			}
			else
			{
				debug_message_buffer("Setpoint refused. Param setpoint accept=0.");
			}
		}
	}
	break;
	default:
		break;
	}
}
Beispiel #7
0
void mavlink_common_message_handler(const mavlink_message_t *msg)
{
  switch (msg->msgid) {
    case MAVLINK_MSG_ID_HEARTBEAT:
      break;

      /* When requesting data streams say we can't send them */
    case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: {
      mavlink_request_data_stream_t cmd;
      mavlink_msg_request_data_stream_decode(msg, &cmd);

      mavlink_msg_data_stream_send(MAVLINK_COMM_0, cmd.req_stream_id, 0, 0);
      MAVLinkSendMessage();
      break;
    }

    /* Override channels with RC */
    case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: {
      mavlink_rc_channels_override_t cmd;
      mavlink_msg_rc_channels_override_decode(msg, &cmd);
#if defined RADIO_CONTROL && defined RADIO_CONTROL_TYPE_DATALINK
      uint8_t thrust = (cmd.chan3_raw - 950) * 127 / 1100;
      int8_t roll = -(cmd.chan1_raw - 1500) * 255 / 1100 / 2;
      int8_t pitch = -(cmd.chan2_raw - 1500) * 255 / 1100 / 2;
      int8_t yaw = -(cmd.chan4_raw - 1500) * 255 / 1100;
      parse_rc_4ch_datalink(0, thrust, roll, pitch, yaw);
      //printf("RECEIVED: RC Channel Override for: %d/%d: throttle: %d; roll: %d; pitch: %d; yaw: %d;\r\n",
      // cmd.target_system, cmd.target_component, thrust, roll, pitch, yaw);
#endif
      break;
    }

    /* When a request is made of the parameters list */
    case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
      mavlink_params_idx = 0;
      break;
    }

    /* When a request os made for a specific parameter */
    case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
      mavlink_param_request_read_t cmd;
      mavlink_msg_param_request_read_decode(msg, &cmd);

      // First check param_index and search for the ID if needed
      if (cmd.param_index == -1) {
        cmd.param_index = settings_idx_from_param_id(cmd.param_id);
      }

      // Send message only if the param_index was found (Coverity Scan)
      if (cmd.param_index > -1) {
        mavlink_msg_param_value_send(MAVLINK_COMM_0,
                                     mavlink_param_names[cmd.param_index],
                                     settings_get_value(cmd.param_index),
                                     MAV_PARAM_TYPE_REAL32,
                                     NB_SETTING,
                                     cmd.param_index);
        MAVLinkSendMessage();
      }
      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 == AC_ID) {
        int16_t idx = settings_idx_from_param_id(set.param_id);

        // setting found
        if (idx >= 0) {
          // Only write if new value is NOT "not-a-number"
          // AND is NOT infinity
          if (set.param_type == MAV_PARAM_TYPE_REAL32 &&
              !isnan(set.param_value) && !isinf(set.param_value)) {
            DlSetting(idx, set.param_value);
            // Report back new value
            mavlink_msg_param_value_send(MAVLINK_COMM_0,
                                         mavlink_param_names[idx],
                                         settings_get_value(idx),
                                         MAV_PARAM_TYPE_REAL32,
                                         NB_SETTING,
                                         idx);
            MAVLinkSendMessage();
          }
        }
      }
    }
    break;

#ifndef AP
    /* only for rotorcraft */
    case MAVLINK_MSG_ID_COMMAND_LONG: {
      mavlink_command_long_t cmd;
      mavlink_msg_command_long_decode(msg, &cmd);
      // Check if this message is for this system
      if ((uint8_t) cmd.target_system == AC_ID) {
        uint8_t result = MAV_RESULT_UNSUPPORTED;
        switch (cmd.command) {
          case MAV_CMD_NAV_GUIDED_ENABLE:
            MAVLINK_DEBUG("got cmd NAV_GUIDED_ENABLE: %f\n", cmd.param1);
            result = MAV_RESULT_FAILED;
            if (cmd.param1 > 0.5) {
              autopilot_set_mode(AP_MODE_GUIDED);
              if (autopilot_mode == AP_MODE_GUIDED) {
                result = MAV_RESULT_ACCEPTED;
              }
            }
            else {
              // turn guided mode off - to what? maybe NAV? or MODE_AUTO2?
            }
            break;

          case MAV_CMD_COMPONENT_ARM_DISARM:
            /* supposed to use this command to arm or SET_MODE?? */
            MAVLINK_DEBUG("got cmd COMPONENT_ARM_DISARM: %f\n", cmd.param1);
            result = MAV_RESULT_FAILED;
            if (cmd.param1 > 0.5) {
              autopilot_set_motors_on(TRUE);
              if (autopilot_motors_on)
                result = MAV_RESULT_ACCEPTED;
            }
            else {
              autopilot_set_motors_on(FALSE);
              if (!autopilot_motors_on)
                result = MAV_RESULT_ACCEPTED;
            }
            break;

          default:
            break;
        }
        // confirm command with result
        mavlink_msg_command_ack_send(MAVLINK_COMM_0, cmd.command, result);
        MAVLinkSendMessage();
      }
      break;
    }

    case MAVLINK_MSG_ID_SET_MODE: {
      mavlink_set_mode_t mode;
      mavlink_msg_set_mode_decode(msg, &mode);
      if (mode.target_system == AC_ID) {
        MAVLINK_DEBUG("got SET_MODE: base_mode:%d\n", mode.base_mode);
        if (mode.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
          autopilot_set_motors_on(TRUE);
        }
        else {
          autopilot_set_motors_on(FALSE);
        }
        if (mode.base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
          autopilot_set_mode(AP_MODE_GUIDED);
        }
        else if (mode.base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
          autopilot_set_mode(AP_MODE_NAV);
        }
      }
      break;
    }

    case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: {
      mavlink_set_position_target_local_ned_t target;
      mavlink_msg_set_position_target_local_ned_decode(msg, &target);
      // Check if this message is for this system
      if (target.target_system == AC_ID) {
        MAVLINK_DEBUG("SET_POSITION_TARGET_LOCAL_NED, byte_mask: %d\n", target.type_mask);
        /* if position and yaw bits are not set to ignored, use only position for now */
        if (!(target.type_mask & 0b1110000000100000)) {
          switch (target.coordinate_frame) {
            case MAV_FRAME_LOCAL_NED:
              MAVLINK_DEBUG("set position target, frame LOCAL_NED\n");
              autopilot_guided_goto_ned(target.x, target.y, target.z, target.yaw);
              break;
            case MAV_FRAME_LOCAL_OFFSET_NED:
              MAVLINK_DEBUG("set position target, frame LOCAL_OFFSET_NED\n");
              autopilot_guided_goto_ned_relative(target.x, target.y, target.z, target.yaw);
              break;
            case MAV_FRAME_BODY_OFFSET_NED:
              MAVLINK_DEBUG("set position target, frame BODY_OFFSET_NED\n");
              autopilot_guided_goto_body_relative(target.x, target.y, target.z, target.yaw);
              break;
            default:
              break;
          }
        }
        else if (!(target.type_mask & 0b0001110000100000)) {
          /* position is set to ignore, but velocity not */
          switch (target.coordinate_frame) {
            case MAV_FRAME_LOCAL_NED:
              MAVLINK_DEBUG("set velocity target, frame LOCAL_NED\n");
              autopilot_guided_move_ned(target.vx, target.vy, target.vz, target.yaw);
              break;
            default:
              break;
          }
        }
      }
      break;
    }
#endif

    default:
      //Do nothing
      MAVLINK_DEBUG("Received message with id: %d\r\n", msg->msgid);
      break;
  }
}
Beispiel #8
0
static void
handle_message(mavlink_message_t *msg)
{
	if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {

		mavlink_command_long_t cmd_mavlink;
		mavlink_msg_command_long_decode(msg, &cmd_mavlink);

		if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid)
				|| (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
			//check for MAVLINK terminate command
			if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
				/* This is the link shutdown command, terminate mavlink */
				warnx("terminating...");
				fflush(stdout);
				usleep(50000);

				/* terminate other threads and this thread */
				thread_should_exit = true;

			} else {

				/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
				vcmd.param1 = cmd_mavlink.param1;
				vcmd.param2 = cmd_mavlink.param2;
				vcmd.param3 = cmd_mavlink.param3;
				vcmd.param4 = cmd_mavlink.param4;
				vcmd.param5 = cmd_mavlink.param5;
				vcmd.param6 = cmd_mavlink.param6;
				vcmd.param7 = cmd_mavlink.param7;
				vcmd.command = cmd_mavlink.command;
				vcmd.target_system = cmd_mavlink.target_system;
				vcmd.target_component = cmd_mavlink.target_component;
				vcmd.source_system = msg->sysid;
				vcmd.source_component = msg->compid;
				vcmd.confirmation =  cmd_mavlink.confirmation;

				/* check if topic is advertised */
				if (cmd_pub <= 0) {
					cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
				}

				/* publish */
				orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
			}
		}
	}

	if (msg->msgid == MAVLINK_MSG_ID_OPTICAL_FLOW) {
		mavlink_optical_flow_t flow;
		mavlink_msg_optical_flow_decode(msg, &flow);

		struct optical_flow_s f;

		f.timestamp = hrt_absolute_time();
		f.flow_raw_x = flow.flow_x;
		f.flow_raw_y = flow.flow_y;
		f.flow_comp_x_m = flow.flow_comp_m_x;
		f.flow_comp_y_m = flow.flow_comp_m_y;
		f.ground_distance_m = flow.ground_distance;
		f.quality = flow.quality;
		f.sensor_id = flow.sensor_id;

		/* check if topic is advertised */
		if (flow_pub <= 0) {
			flow_pub = orb_advertise(ORB_ID(optical_flow), &f);

		} else {
			/* publish */
			orb_publish(ORB_ID(optical_flow), flow_pub, &f);
		}

	}

	if (msg->msgid == MAVLINK_MSG_ID_SET_MODE) {
		/* Set mode on request */
		mavlink_set_mode_t new_mode;
		mavlink_msg_set_mode_decode(msg, &new_mode);

		/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
		vcmd.param1 = new_mode.base_mode;
		vcmd.param2 = new_mode.custom_mode;
		vcmd.param3 = 0;
		vcmd.param4 = 0;
		vcmd.param5 = 0;
		vcmd.param6 = 0;
		vcmd.param7 = 0;
		vcmd.command = MAV_CMD_DO_SET_MODE;
		vcmd.target_system = new_mode.target_system;
		vcmd.target_component = MAV_COMP_ID_ALL;
		vcmd.source_system = msg->sysid;
		vcmd.source_component = msg->compid;
		vcmd.confirmation = 1;

		/* check if topic is advertised */
		if (cmd_pub <= 0) {
			cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);

		} else {
			/* create command */
			orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
		}
	}

	/* Handle Vicon position estimates */
	if (msg->msgid == MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE) {
		mavlink_vicon_position_estimate_t pos;
		mavlink_msg_vicon_position_estimate_decode(msg, &pos);

		vicon_position.x = pos.x;
		vicon_position.y = pos.y;
		vicon_position.z = pos.z;

		if (vicon_position_pub <= 0) {
			vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position);

		} else {
			orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position);
		}
	}

	//Mavlink Message from the onboard computer / laserscanner:
	if (msg->msgid == MAVLINK_MSG_ID_DANGER) {
			mavlink_danger_t dang;
			mavlink_msg_danger_decode(msg, &dang);

			struct danger_s d;

			d.time_usec = hrt_absolute_time();
			d.sensor_id = dang.sensor_id;
			d.danger_level = dang.danger_level;
			d.danger_dist = dang.danger_dist;
			d.danger_dir = dang.danger_dir;
			d.avoid_level = dang.avoid_level;
			d.avoid_dir = dang.avoid_dir;
			//check if topic is advertised
			if (danger_pub <= 0) {
				danger_pub = orb_advertise(ORB_ID(danger), &d);
			} else {
				// publish
				orb_publish(ORB_ID(danger), danger_pub, &d);
			}
		}

	/* Handle quadrotor motor setpoints */

	if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) {
		mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint;
		mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);

		if (mavlink_system.sysid < 4) {

			/* switch to a receiving link mode */
			gcs_link = false;

			/*
			 * rate control mode - defined by MAVLink
			 */

			uint8_t ml_mode = 0;
			bool ml_armed = false;

			switch (quad_motors_setpoint.mode) {
			case 0:
				ml_armed = false;
				break;

			case 1:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
				ml_armed = true;

				break;

			case 2:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
				ml_armed = true;

				break;

			case 3:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
				break;

			case 4:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
				break;
			}

			offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1]   / (float)INT16_MAX;
			offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1]  / (float)INT16_MAX;
			offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1]    / (float)INT16_MAX;
			offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;

			if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) {
				ml_armed = false;
			}

			offboard_control_sp.armed = ml_armed;
			offboard_control_sp.mode = ml_mode;

			offboard_control_sp.timestamp = hrt_absolute_time();

			/* check if topic has to be advertised */
			if (offboard_control_sp_pub <= 0) {
				offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);

			} else {
				/* Publish */
				orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp);
			}
		}
	}

}
Beispiel #9
0
static void
handle_message(mavlink_message_t *msg)
{
	if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {

		mavlink_command_long_t cmd_mavlink;
		mavlink_msg_command_long_decode(msg, &cmd_mavlink);

		if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid)
				|| (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
			//check for MAVLINK terminate command
			if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
				/* This is the link shutdown command, terminate mavlink */
				printf("[mavlink] Terminating .. \n");
				fflush(stdout);
				usleep(50000);

				/* terminate other threads and this thread */
				thread_should_exit = true;

			} else {

				/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
				vcmd.param1 = cmd_mavlink.param1;
				vcmd.param2 = cmd_mavlink.param2;
				vcmd.param3 = cmd_mavlink.param3;
				vcmd.param4 = cmd_mavlink.param4;
				vcmd.param5 = cmd_mavlink.param5;
				vcmd.param6 = cmd_mavlink.param6;
				vcmd.param7 = cmd_mavlink.param7;
				// XXX do proper translation
				vcmd.command = (enum VEHICLE_CMD)cmd_mavlink.command;
				vcmd.target_system = cmd_mavlink.target_system;
				vcmd.target_component = cmd_mavlink.target_component;
				vcmd.source_system = msg->sysid;
				vcmd.source_component = msg->compid;
				vcmd.confirmation =  cmd_mavlink.confirmation;

				/* check if topic is advertised */
				if (cmd_pub <= 0) {
					cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);

				} else {
					/* publish */
					orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
				}
			}
		}
	}

	if (msg->msgid == MAVLINK_MSG_ID_OPTICAL_FLOW) {
		mavlink_optical_flow_t flow;
		mavlink_msg_optical_flow_decode(msg, &flow);

		struct optical_flow_s f;

		f.timestamp = flow.time_usec;
		f.flow_raw_x = flow.flow_x;
		f.flow_raw_y = flow.flow_y;
		f.flow_comp_x_m = flow.flow_comp_m_x;
		f.flow_comp_y_m = flow.flow_comp_m_y;
		f.ground_distance_m = flow.ground_distance;
		f.quality = flow.quality;
		f.sensor_id = flow.sensor_id;

		/* check if topic is advertised */
		if (flow_pub <= 0) {
			flow_pub = orb_advertise(ORB_ID(optical_flow), &f);

		} else {
			/* publish */
			orb_publish(ORB_ID(optical_flow), flow_pub, &f);
		}
	}

	if (msg->msgid == MAVLINK_MSG_ID_SET_MODE) {
		/* Set mode on request */
		mavlink_set_mode_t new_mode;
		mavlink_msg_set_mode_decode(msg, &new_mode);

		union px4_custom_mode custom_mode;
		custom_mode.data = new_mode.custom_mode;
		/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
		vcmd.param1 = new_mode.base_mode;
		vcmd.param2 = custom_mode.main_mode;
		vcmd.param3 = 0;
		vcmd.param4 = 0;
		vcmd.param5 = 0;
		vcmd.param6 = 0;
		vcmd.param7 = 0;
		vcmd.command = VEHICLE_CMD_DO_SET_MODE;
		vcmd.target_system = new_mode.target_system;
		vcmd.target_component = MAV_COMP_ID_ALL;
		vcmd.source_system = msg->sysid;
		vcmd.source_component = msg->compid;
		vcmd.confirmation = 1;

		/* check if topic is advertised */
		if (cmd_pub <= 0) {
			cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);

		} else {
			/* create command */
			orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
		}
	}

	/* Handle Vicon position estimates */
	if (msg->msgid == MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE) {
		mavlink_vicon_position_estimate_t pos;
		mavlink_msg_vicon_position_estimate_decode(msg, &pos);

		vicon_position.timestamp = hrt_absolute_time();

		vicon_position.x = pos.x;
		vicon_position.y = pos.y;
		vicon_position.z = pos.z;

		vicon_position.roll = pos.roll;
		vicon_position.pitch = pos.pitch;
		vicon_position.yaw = pos.yaw;

		if (vicon_position_pub <= 0) {
			vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position);

		} else {
			orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position);
		}
	}

	/* Handle quadrotor motor setpoints */

	if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) {
		mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint;
		mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);

		if (mavlink_system.sysid < 4) {

			/* switch to a receiving link mode */
			gcs_link = false;

			/*
			 * rate control mode - defined by MAVLink
			 */

			uint8_t ml_mode = 0;
			bool ml_armed = false;

			switch (quad_motors_setpoint.mode) {
			case 0:
				ml_armed = false;
				break;

			case 1:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
				ml_armed = true;

				break;

			case 2:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
				ml_armed = true;

				break;

			case 3:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
				break;

			case 4:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
				break;
			}

			offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1]   / (float)INT16_MAX;
			offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1]  / (float)INT16_MAX;
			offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1]    / (float)INT16_MAX;
			offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;

			if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) {
				ml_armed = false;
			}

			offboard_control_sp.armed = ml_armed;
			offboard_control_sp.mode = static_cast<enum OFFBOARD_CONTROL_MODE>(ml_mode);

			offboard_control_sp.timestamp = hrt_absolute_time();

			/* check if topic has to be advertised */
			if (offboard_control_sp_pub <= 0) {
				offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);

			} else {
				/* Publish */
				orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp);
			}
		}
	}

	/* handle status updates of the radio */
	if (msg->msgid == MAVLINK_MSG_ID_RADIO_STATUS) {

		struct telemetry_status_s tstatus;

		mavlink_radio_status_t rstatus;
		mavlink_msg_radio_status_decode(msg, &rstatus);

		/* publish telemetry status topic */
		tstatus.timestamp = hrt_absolute_time();
		tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO;
		tstatus.rssi = rstatus.rssi;
		tstatus.remote_rssi = rstatus.remrssi;
		tstatus.txbuf = rstatus.txbuf;
		tstatus.noise = rstatus.noise;
		tstatus.remote_noise = rstatus.remnoise;
		tstatus.rxerrors = rstatus.rxerrors;
		tstatus.fixed = rstatus.fixed;

		if (telemetry_status_pub == 0) {
			telemetry_status_pub = orb_advertise(ORB_ID(telemetry_status), &tstatus);

		} else {
			orb_publish(ORB_ID(telemetry_status), telemetry_status_pub, &tstatus);
		}
	}

	/*
	 * Only decode hil messages in HIL mode.
	 *
	 * The HIL mode is enabled by the HIL bit flag
	 * in the system mode. Either send a set mode
	 * COMMAND_LONG message or a SET_MODE message
	 */

	if (mavlink_hil_enabled) {

		uint64_t timestamp = hrt_absolute_time();

		if (msg->msgid == MAVLINK_MSG_ID_HIL_SENSOR) {

			mavlink_hil_sensor_t imu;
			mavlink_msg_hil_sensor_decode(msg, &imu);

			/* sensors general */
			hil_sensors.timestamp = hrt_absolute_time();

			/* hil gyro */
			static const float mrad2rad = 1.0e-3f;
			hil_sensors.gyro_counter = hil_counter;
			hil_sensors.gyro_raw[0] = imu.xgyro / mrad2rad;
			hil_sensors.gyro_raw[1] = imu.ygyro / mrad2rad;
			hil_sensors.gyro_raw[2] = imu.zgyro / mrad2rad;
			hil_sensors.gyro_rad_s[0] = imu.xgyro;
			hil_sensors.gyro_rad_s[1] = imu.ygyro;
			hil_sensors.gyro_rad_s[2] = imu.zgyro;

			/* accelerometer */
			hil_sensors.accelerometer_counter = hil_counter;
			static const float mg2ms2 = 9.8f / 1000.0f;
			hil_sensors.accelerometer_raw[0] = imu.xacc / mg2ms2;
			hil_sensors.accelerometer_raw[1] = imu.yacc / mg2ms2;
			hil_sensors.accelerometer_raw[2] = imu.zacc / mg2ms2;
			hil_sensors.accelerometer_m_s2[0] = imu.xacc;
			hil_sensors.accelerometer_m_s2[1] = imu.yacc;
			hil_sensors.accelerometer_m_s2[2] = imu.zacc;
			hil_sensors.accelerometer_mode = 0; // TODO what is this?
			hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16

			/* adc */
			hil_sensors.adc_voltage_v[0] = 0.0f;
			hil_sensors.adc_voltage_v[1] = 0.0f;
			hil_sensors.adc_voltage_v[2] = 0.0f;

			/* magnetometer */
			float mga2ga = 1.0e-3f;
			hil_sensors.magnetometer_counter = hil_counter;
			hil_sensors.magnetometer_raw[0] = imu.xmag / mga2ga;
			hil_sensors.magnetometer_raw[1] = imu.ymag / mga2ga;
			hil_sensors.magnetometer_raw[2] = imu.zmag / mga2ga;
			hil_sensors.magnetometer_ga[0] = imu.xmag;
			hil_sensors.magnetometer_ga[1] = imu.ymag;
			hil_sensors.magnetometer_ga[2] = imu.zmag;
			hil_sensors.magnetometer_range_ga = 32.7f; // int16
			hil_sensors.magnetometer_mode = 0; // TODO what is this
			hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f;

			/* baro */
			hil_sensors.baro_pres_mbar = imu.abs_pressure;
			hil_sensors.baro_alt_meter = imu.pressure_alt;
			hil_sensors.baro_temp_celcius = imu.temperature;

			hil_sensors.gyro_counter = hil_counter;
			hil_sensors.magnetometer_counter = hil_counter;
			hil_sensors.accelerometer_counter = hil_counter;

			/* differential pressure */
			hil_sensors.differential_pressure_pa = imu.diff_pressure * 1e2f; //from hPa to Pa
			hil_sensors.differential_pressure_counter = hil_counter;

			/* airspeed from differential pressure, ambient pressure and temp */
			struct airspeed_s airspeed;

			float ias = calc_indicated_airspeed(hil_sensors.differential_pressure_pa);
			// XXX need to fix this
			float tas = ias;

			airspeed.timestamp = hrt_absolute_time();
			airspeed.indicated_airspeed_m_s = ias;
			airspeed.true_airspeed_m_s = tas;

			if (pub_hil_airspeed < 0) {
				pub_hil_airspeed = orb_advertise(ORB_ID(airspeed), &airspeed);

			} else {
				orb_publish(ORB_ID(airspeed), pub_hil_airspeed, &airspeed);
			}

			//warnx("SENSOR: IAS: %6.2f TAS: %6.2f", airspeed.indicated_airspeed_m_s, airspeed.true_airspeed_m_s);

			/* individual sensor publications */
			struct gyro_report gyro;
			gyro.x_raw = imu.xgyro / mrad2rad;
			gyro.y_raw = imu.ygyro / mrad2rad;
			gyro.z_raw = imu.zgyro / mrad2rad;
			gyro.x = imu.xgyro;
			gyro.y = imu.ygyro;
			gyro.z = imu.zgyro;
			gyro.temperature = imu.temperature;
			gyro.timestamp = hrt_absolute_time();

			if (pub_hil_gyro < 0) {
				pub_hil_gyro = orb_advertise(ORB_ID(sensor_gyro), &gyro);

			} else {
				orb_publish(ORB_ID(sensor_gyro), pub_hil_gyro, &gyro);
			}

			struct accel_report accel;

			accel.x_raw = imu.xacc / mg2ms2;

			accel.y_raw = imu.yacc / mg2ms2;

			accel.z_raw = imu.zacc / mg2ms2;

			accel.x = imu.xacc;

			accel.y = imu.yacc;

			accel.z = imu.zacc;

			accel.temperature = imu.temperature;

			accel.timestamp = hrt_absolute_time();

			if (pub_hil_accel < 0) {
				pub_hil_accel = orb_advertise(ORB_ID(sensor_accel), &accel);

			} else {
				orb_publish(ORB_ID(sensor_accel), pub_hil_accel, &accel);
			}

			struct mag_report mag;

			mag.x_raw = imu.xmag / mga2ga;

			mag.y_raw = imu.ymag / mga2ga;

			mag.z_raw = imu.zmag / mga2ga;

			mag.x = imu.xmag;

			mag.y = imu.ymag;

			mag.z = imu.zmag;

			mag.timestamp = hrt_absolute_time();

			if (pub_hil_mag < 0) {
				pub_hil_mag = orb_advertise(ORB_ID(sensor_mag), &mag);

			} else {
				orb_publish(ORB_ID(sensor_mag), pub_hil_mag, &mag);
			}

			struct baro_report baro;

			baro.pressure = imu.abs_pressure;

			baro.altitude = imu.pressure_alt;

			baro.temperature = imu.temperature;

			baro.timestamp = hrt_absolute_time();

			if (pub_hil_baro < 0) {
				pub_hil_baro = orb_advertise(ORB_ID(sensor_baro), &baro);

			} else {
				orb_publish(ORB_ID(sensor_baro), pub_hil_baro, &baro);
			}

			/* publish combined sensor topic */
			if (pub_hil_sensors > 0) {
				orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors);

			} else {
				pub_hil_sensors = orb_advertise(ORB_ID(sensor_combined), &hil_sensors);
			}

			/* fill in HIL battery status */
			hil_battery_status.timestamp = hrt_absolute_time();
			hil_battery_status.voltage_v = 11.1f;
			hil_battery_status.current_a = 10.0f;

			/* lazily publish the battery voltage */
			if (pub_hil_battery > 0) {
				orb_publish(ORB_ID(battery_status), pub_hil_battery, &hil_battery_status);

			} else {
				pub_hil_battery = orb_advertise(ORB_ID(battery_status), &hil_battery_status);
			}

			// increment counters
			hil_counter++;
			hil_frames++;

			// output
			if ((timestamp - old_timestamp) > 10000000) {
				printf("receiving hil sensor at %d hz\n", hil_frames / 10);
				old_timestamp = timestamp;
				hil_frames = 0;
			}
		}

		if (msg->msgid == MAVLINK_MSG_ID_HIL_GPS) {

			mavlink_hil_gps_t gps;
			mavlink_msg_hil_gps_decode(msg, &gps);

			/* gps */
			hil_gps.timestamp_position = gps.time_usec;
			hil_gps.time_gps_usec = gps.time_usec;
			hil_gps.lat = gps.lat;
			hil_gps.lon = gps.lon;
			hil_gps.alt = gps.alt;
			hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m
			hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m
			hil_gps.s_variance_m_s = 5.0f;
			hil_gps.p_variance_m = hil_gps.eph_m * hil_gps.eph_m;
			hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s

			/* gps.cog is in degrees 0..360 * 100, heading is -PI..+PI */
			float heading_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f;

			/* go back to -PI..PI */
			if (heading_rad > M_PI_F)
				heading_rad -= 2.0f * M_PI_F;

			hil_gps.vel_n_m_s = gps.vn * 1e-2f; // from cm to m
			hil_gps.vel_e_m_s = gps.ve * 1e-2f; // from cm to m
			hil_gps.vel_d_m_s = gps.vd * 1e-2f; // from cm to m
			hil_gps.vel_ned_valid = true;
			/* COG (course over ground) is spec'ed as -PI..+PI */
			hil_gps.cog_rad = heading_rad;
			hil_gps.fix_type = gps.fix_type;
			hil_gps.satellites_visible = gps.satellites_visible;

			/* publish GPS measurement data */
			if (pub_hil_gps > 0) {
				orb_publish(ORB_ID(vehicle_gps_position), pub_hil_gps, &hil_gps);

			} else {
				pub_hil_gps = orb_advertise(ORB_ID(vehicle_gps_position), &hil_gps);
			}

		}

		if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE_QUATERNION) {

			mavlink_hil_state_quaternion_t hil_state;
			mavlink_msg_hil_state_quaternion_decode(msg, &hil_state);

			struct airspeed_s airspeed;
			airspeed.timestamp = hrt_absolute_time();
			airspeed.indicated_airspeed_m_s = hil_state.ind_airspeed * 1e-2f;
			airspeed.true_airspeed_m_s = hil_state.true_airspeed * 1e-2f;

			if (pub_hil_airspeed < 0) {
				pub_hil_airspeed = orb_advertise(ORB_ID(airspeed), &airspeed);

			} else {
				orb_publish(ORB_ID(airspeed), pub_hil_airspeed, &airspeed);
			}

			uint64_t timestamp = hrt_absolute_time();

			// publish global position	
			if (pub_hil_global_pos > 0) {
				orb_publish(ORB_ID(vehicle_global_position), pub_hil_global_pos, &hil_global_pos);
				// global position packet
				hil_global_pos.timestamp = timestamp;
				hil_global_pos.valid = true;
				hil_global_pos.lat = hil_state.lat;
				hil_global_pos.lon = hil_state.lon;
				hil_global_pos.alt = hil_state.alt / 1000.0f;
				hil_global_pos.vx = hil_state.vx / 100.0f;
				hil_global_pos.vy = hil_state.vy / 100.0f;
				hil_global_pos.vz = hil_state.vz / 100.0f;

			} else {
				pub_hil_global_pos = orb_advertise(ORB_ID(vehicle_global_position), &hil_global_pos);
			}

			// publish local position
			if (pub_hil_local_pos > 0) {
				float x;
				float y;
				bool landed = hil_state.alt/1000.0f < (alt0 + 0.1); // XXX improve?
				double lat = hil_state.lat*1e-7;
				double lon = hil_state.lon*1e-7;
				map_projection_project(lat, lon, &x, &y); 
				hil_local_pos.timestamp = timestamp;
				hil_local_pos.xy_valid = true;
				hil_local_pos.z_valid = true;
				hil_local_pos.v_xy_valid = true;
				hil_local_pos.v_z_valid = true;
				hil_local_pos.x = x;
				hil_local_pos.y = y;
				hil_local_pos.z = alt0 - hil_state.alt/1000.0f;
				hil_local_pos.vx = hil_state.vx/100.0f;
				hil_local_pos.vy = hil_state.vy/100.0f;
				hil_local_pos.vz = hil_state.vz/100.0f;
				hil_local_pos.yaw = hil_attitude.yaw;
				hil_local_pos.xy_global = true;
				hil_local_pos.z_global = true;
				hil_local_pos.ref_timestamp = timestamp;
				hil_local_pos.ref_lat = hil_state.lat;
				hil_local_pos.ref_lon = hil_state.lon;
				hil_local_pos.ref_alt = alt0;
				hil_local_pos.landed = landed;
				orb_publish(ORB_ID(vehicle_local_position), pub_hil_local_pos, &hil_local_pos);
			} else {
				pub_hil_local_pos = orb_advertise(ORB_ID(vehicle_local_position), &hil_local_pos);
				lat0 = hil_state.lat;
				lon0 = hil_state.lon;
				alt0 = hil_state.alt / 1000.0f;
				map_projection_init(hil_state.lat, hil_state.lon);
			}

			/* Calculate Rotation Matrix */
			math::Quaternion q(hil_state.attitude_quaternion);
			math::Dcm C_nb(q);
			math::EulerAngles euler(C_nb);

			/* set rotation matrix */
			for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
					hil_attitude.R[i][j] = C_nb(i, j);

			hil_attitude.R_valid = true;

			/* set quaternion */
			hil_attitude.q[0] = q(0);
			hil_attitude.q[1] = q(1);
			hil_attitude.q[2] = q(2);
			hil_attitude.q[3] = q(3);
			hil_attitude.q_valid = true;

			hil_attitude.roll = euler.getPhi();
			hil_attitude.pitch = euler.getTheta();
			hil_attitude.yaw = euler.getPsi();
			hil_attitude.rollspeed = hil_state.rollspeed;
			hil_attitude.pitchspeed = hil_state.pitchspeed;
			hil_attitude.yawspeed = hil_state.yawspeed;

			/* set timestamp and notify processes (broadcast) */
			hil_attitude.timestamp = hrt_absolute_time();

			if (pub_hil_attitude > 0) {
				orb_publish(ORB_ID(vehicle_attitude), pub_hil_attitude, &hil_attitude);

			} else {
				pub_hil_attitude = orb_advertise(ORB_ID(vehicle_attitude), &hil_attitude);
			}

			struct accel_report accel;

			accel.x_raw = hil_state.xacc / 9.81f * 1e3f;

			accel.y_raw = hil_state.yacc / 9.81f * 1e3f;

			accel.z_raw = hil_state.zacc / 9.81f * 1e3f;

			accel.x = hil_state.xacc;

			accel.y = hil_state.yacc;

			accel.z = hil_state.zacc;

			accel.temperature = 25.0f;

			accel.timestamp = hrt_absolute_time();

			if (pub_hil_accel < 0) {
				pub_hil_accel = orb_advertise(ORB_ID(sensor_accel), &accel);

			} else {
				orb_publish(ORB_ID(sensor_accel), pub_hil_accel, &accel);
			}

			/* fill in HIL battery status */
			hil_battery_status.timestamp = hrt_absolute_time();
			hil_battery_status.voltage_v = 11.1f;
			hil_battery_status.current_a = 10.0f;

			/* lazily publish the battery voltage */
			if (pub_hil_battery > 0) {
				orb_publish(ORB_ID(battery_status), pub_hil_battery, &hil_battery_status);

			} else {
				pub_hil_battery = orb_advertise(ORB_ID(battery_status), &hil_battery_status);
			}
		}

		if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
			mavlink_manual_control_t man;
			mavlink_msg_manual_control_decode(msg, &man);

			struct rc_channels_s rc_hil;
			memset(&rc_hil, 0, sizeof(rc_hil));
			static orb_advert_t rc_pub = 0;

			rc_hil.timestamp = hrt_absolute_time();
			rc_hil.chan_count = 4;

			rc_hil.chan[0].scaled = man.x / 1000.0f;
			rc_hil.chan[1].scaled = man.y / 1000.0f;
			rc_hil.chan[2].scaled = man.r / 1000.0f;
			rc_hil.chan[3].scaled = man.z / 1000.0f;

			struct manual_control_setpoint_s mc;
			static orb_advert_t mc_pub = 0;

			int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));

			/* get a copy first, to prevent altering values that are not sent by the mavlink command */
			orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &mc);

			mc.timestamp = rc_hil.timestamp;
			mc.roll = man.x / 1000.0f;
			mc.pitch = man.y / 1000.0f;
			mc.yaw = man.r / 1000.0f;
			mc.throttle = man.z / 1000.0f;

			/* fake RC channels with manual control input from simulator */


			if (rc_pub == 0) {
				rc_pub = orb_advertise(ORB_ID(rc_channels), &rc_hil);

			} else {
				orb_publish(ORB_ID(rc_channels), rc_pub, &rc_hil);
			}

			if (mc_pub == 0) {
				mc_pub = orb_advertise(ORB_ID(manual_control_setpoint), &mc);

			} else {
				orb_publish(ORB_ID(manual_control_setpoint), mc_pub, &mc);
			}
		}
	}
}
Beispiel #10
0
static void
handle_message(mavlink_message_t *msg)
{
	if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {

		mavlink_command_long_t cmd_mavlink;
		mavlink_msg_command_long_decode(msg, &cmd_mavlink);

		if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid)
				|| (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
			//check for MAVLINK terminate command
			if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
				/* This is the link shutdown command, terminate mavlink */
				printf("[mavlink] Terminating .. \n");
				fflush(stdout);
				usleep(50000);

				/* terminate other threads and this thread */
				thread_should_exit = true;

			} else {

				/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
				vcmd.param1 = cmd_mavlink.param1;
				vcmd.param2 = cmd_mavlink.param2;
				vcmd.param3 = cmd_mavlink.param3;
				vcmd.param4 = cmd_mavlink.param4;
				vcmd.param5 = cmd_mavlink.param5;
				vcmd.param6 = cmd_mavlink.param6;
				vcmd.param7 = cmd_mavlink.param7;
				vcmd.command = cmd_mavlink.command;
				vcmd.target_system = cmd_mavlink.target_system;
				vcmd.target_component = cmd_mavlink.target_component;
				vcmd.source_system = msg->sysid;
				vcmd.source_component = msg->compid;
				vcmd.confirmation =  cmd_mavlink.confirmation;

				/* check if topic is advertised */
				if (cmd_pub <= 0) {
					cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
				}

				/* publish */
				orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
			}
		}
	}

	if (msg->msgid == MAVLINK_MSG_ID_OPTICAL_FLOW) {
		mavlink_optical_flow_t flow;
		mavlink_msg_optical_flow_decode(msg, &flow);

		struct optical_flow_s f;

		f.timestamp = flow.time_usec;
		f.flow_raw_x = flow.flow_x;
		f.flow_raw_y = flow.flow_y;
		f.flow_comp_x_m = flow.flow_comp_m_x;
		f.flow_comp_y_m = flow.flow_comp_m_y;
		f.ground_distance_m = flow.ground_distance;
		f.quality = flow.quality;
		f.sensor_id = flow.sensor_id;

		/* check if topic is advertised */
		if (flow_pub <= 0) {
			flow_pub = orb_advertise(ORB_ID(optical_flow), &f);

		} else {
			/* publish */
			orb_publish(ORB_ID(optical_flow), flow_pub, &f);
		}
	}

	if (msg->msgid == MAVLINK_MSG_ID_SET_MODE) {
		/* Set mode on request */
		mavlink_set_mode_t new_mode;
		mavlink_msg_set_mode_decode(msg, &new_mode);

		/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
		vcmd.param1 = new_mode.base_mode;
		vcmd.param2 = new_mode.custom_mode;
		vcmd.param3 = 0;
		vcmd.param4 = 0;
		vcmd.param5 = 0;
		vcmd.param6 = 0;
		vcmd.param7 = 0;
		vcmd.command = MAV_CMD_DO_SET_MODE;
		vcmd.target_system = new_mode.target_system;
		vcmd.target_component = MAV_COMP_ID_ALL;
		vcmd.source_system = msg->sysid;
		vcmd.source_component = msg->compid;
		vcmd.confirmation = 1;

		/* check if topic is advertised */
		if (cmd_pub <= 0) {
			cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);

		} else {
			/* create command */
			orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
		}
	}

	/* Handle Vicon position estimates */
	if (msg->msgid == MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE) {
		mavlink_vicon_position_estimate_t pos;
		mavlink_msg_vicon_position_estimate_decode(msg, &pos);

		vicon_position.timestamp = hrt_absolute_time();

		vicon_position.x = pos.x;
		vicon_position.y = pos.y;
		vicon_position.z = pos.z;

		vicon_position.roll = pos.roll;
		vicon_position.pitch = pos.pitch;
		vicon_position.yaw = pos.yaw;

		if (vicon_position_pub <= 0) {
			vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position);

		} else {
			orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position);
		}
	}

	/* Handle quadrotor motor setpoints */

	if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) {
		mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint;
		mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);

		if (mavlink_system.sysid < 4) {

			/* switch to a receiving link mode */
			gcs_link = false;

			/*
			 * rate control mode - defined by MAVLink
			 */

			uint8_t ml_mode = 0;
			bool ml_armed = false;

			switch (quad_motors_setpoint.mode) {
			case 0:
				ml_armed = false;
				break;

			case 1:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
				ml_armed = true;

				break;

			case 2:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
				ml_armed = true;

				break;

			case 3:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
				break;

			case 4:
				ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
				break;
			}

			offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1]   / (float)INT16_MAX;
			offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1]  / (float)INT16_MAX;
			offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1]    / (float)INT16_MAX;
			offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;

			if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) {
				ml_armed = false;
			}

			offboard_control_sp.armed = ml_armed;
			offboard_control_sp.mode = ml_mode;

			offboard_control_sp.timestamp = hrt_absolute_time();

			/* check if topic has to be advertised */
			if (offboard_control_sp_pub <= 0) {
				offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);

			} else {
				/* Publish */
				orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp);
			}
		}
	}

	/*
	 * Only decode hil messages in HIL mode.
	 *
	 * The HIL mode is enabled by the HIL bit flag
	 * in the system mode. Either send a set mode
	 * COMMAND_LONG message or a SET_MODE message
	 */

	if (mavlink_hil_enabled) {

		uint64_t timestamp = hrt_absolute_time();

		/* TODO, set ground_press/ temp during calib */
		static const float ground_press = 1013.25f; // mbar
		static const float ground_tempC = 21.0f;
		static const float ground_alt = 0.0f;
		static const float T0 = 273.15;
		static const float R = 287.05f;
		static const float g = 9.806f;

		if (msg->msgid == MAVLINK_MSG_ID_RAW_IMU) {

			mavlink_raw_imu_t imu;
			mavlink_msg_raw_imu_decode(msg, &imu);

			/* packet counter */
			static uint16_t hil_counter = 0;
			static uint16_t hil_frames = 0;
			static uint64_t old_timestamp = 0;

			/* sensors general */
			hil_sensors.timestamp = imu.time_usec;

			/* hil gyro */
			static const float mrad2rad = 1.0e-3f;
			hil_sensors.gyro_counter = hil_counter;
			hil_sensors.gyro_raw[0] = imu.xgyro;
			hil_sensors.gyro_raw[1] = imu.ygyro;
			hil_sensors.gyro_raw[2] = imu.zgyro;
			hil_sensors.gyro_rad_s[0] = imu.xgyro * mrad2rad;
			hil_sensors.gyro_rad_s[1] = imu.ygyro * mrad2rad;
			hil_sensors.gyro_rad_s[2] = imu.zgyro * mrad2rad;

			/* accelerometer */
			hil_sensors.accelerometer_counter = hil_counter;
			static const float mg2ms2 = 9.8f / 1000.0f;
			hil_sensors.accelerometer_raw[0] = imu.xacc;
			hil_sensors.accelerometer_raw[1] = imu.yacc;
			hil_sensors.accelerometer_raw[2] = imu.zacc;
			hil_sensors.accelerometer_m_s2[0] = mg2ms2 * imu.xacc;
			hil_sensors.accelerometer_m_s2[1] = mg2ms2 * imu.yacc;
			hil_sensors.accelerometer_m_s2[2] = mg2ms2 * imu.zacc;
			hil_sensors.accelerometer_mode = 0; // TODO what is this?
			hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16

			/* adc */
			hil_sensors.adc_voltage_v[0] = 0;
			hil_sensors.adc_voltage_v[1] = 0;
			hil_sensors.adc_voltage_v[2] = 0;

			/* magnetometer */
			float mga2ga = 1.0e-3f;
			hil_sensors.magnetometer_counter = hil_counter;
			hil_sensors.magnetometer_raw[0] = imu.xmag;
			hil_sensors.magnetometer_raw[1] = imu.ymag;
			hil_sensors.magnetometer_raw[2] = imu.zmag;
			hil_sensors.magnetometer_ga[0] = imu.xmag * mga2ga;
			hil_sensors.magnetometer_ga[1] = imu.ymag * mga2ga;
			hil_sensors.magnetometer_ga[2] = imu.zmag * mga2ga;
			hil_sensors.magnetometer_range_ga = 32.7f; // int16
			hil_sensors.magnetometer_mode = 0; // TODO what is this
			hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f;

			/* publish */
			orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors);

			// increment counters
			hil_counter += 1 ;
			hil_frames += 1 ;

			// output
			if ((timestamp - old_timestamp) > 10000000) {
				printf("receiving hil imu at %d hz\n", hil_frames/10);
				old_timestamp = timestamp;
				hil_frames = 0;
			}
		}

		if (msg->msgid == MAVLINK_MSG_ID_HIGHRES_IMU) {

			mavlink_highres_imu_t imu;
			mavlink_msg_highres_imu_decode(msg, &imu);

			/* packet counter */
			static uint16_t hil_counter = 0;
			static uint16_t hil_frames = 0;
			static uint64_t old_timestamp = 0;

			/* sensors general */
			hil_sensors.timestamp = imu.time_usec;

			/* hil gyro */
			static const float mrad2rad = 1.0e-3f;
			hil_sensors.gyro_counter = hil_counter;
			hil_sensors.gyro_raw[0] = imu.xgyro / mrad2rad;
			hil_sensors.gyro_raw[1] = imu.ygyro / mrad2rad;
			hil_sensors.gyro_raw[2] = imu.zgyro / mrad2rad;
			hil_sensors.gyro_rad_s[0] = imu.xgyro;
			hil_sensors.gyro_rad_s[1] = imu.ygyro;
			hil_sensors.gyro_rad_s[2] = imu.zgyro;

			/* accelerometer */
			hil_sensors.accelerometer_counter = hil_counter;
			static const float mg2ms2 = 9.8f / 1000.0f;
			hil_sensors.accelerometer_raw[0] = imu.xacc / mg2ms2;
			hil_sensors.accelerometer_raw[1] = imu.yacc / mg2ms2;
			hil_sensors.accelerometer_raw[2] = imu.zacc / mg2ms2;
			hil_sensors.accelerometer_m_s2[0] = imu.xacc;
			hil_sensors.accelerometer_m_s2[1] = imu.yacc;
			hil_sensors.accelerometer_m_s2[2] = imu.zacc;
			hil_sensors.accelerometer_mode = 0; // TODO what is this?
			hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16

			/* adc */
			hil_sensors.adc_voltage_v[0] = 0;
			hil_sensors.adc_voltage_v[1] = 0;
			hil_sensors.adc_voltage_v[2] = 0;

			/* magnetometer */
			float mga2ga = 1.0e-3f;
			hil_sensors.magnetometer_counter = hil_counter;
			hil_sensors.magnetometer_raw[0] = imu.xmag / mga2ga;
			hil_sensors.magnetometer_raw[1] = imu.ymag / mga2ga;
			hil_sensors.magnetometer_raw[2] = imu.zmag / mga2ga;
			hil_sensors.magnetometer_ga[0] = imu.xmag;
			hil_sensors.magnetometer_ga[1] = imu.ymag;
			hil_sensors.magnetometer_ga[2] = imu.zmag;
			hil_sensors.magnetometer_range_ga = 32.7f; // int16
			hil_sensors.magnetometer_mode = 0; // TODO what is this
			hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f;

			hil_sensors.baro_pres_mbar = imu.abs_pressure;

			float tempC =  imu.temperature;
			float tempAvgK = T0 + (tempC + ground_tempC) / 2.0f;
			float h =  ground_alt + (R / g) * tempAvgK * logf(ground_press / imu.abs_pressure);

			hil_sensors.baro_alt_meter = h;
			hil_sensors.baro_temp_celcius = imu.temperature;

			/* publish */
			orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors);

			// increment counters
			hil_counter += 1 ;
			hil_frames += 1 ;

			// output
			if ((timestamp - old_timestamp) > 10000000) {
				printf("receiving hil imu at %d hz\n", hil_frames/10);
				old_timestamp = timestamp;
				hil_frames = 0;
			}
		}

		if (msg->msgid == MAVLINK_MSG_ID_GPS_RAW_INT) {

			mavlink_gps_raw_int_t gps;
			mavlink_msg_gps_raw_int_decode(msg, &gps);

			/* packet counter */
			static uint16_t hil_counter = 0;
			static uint16_t hil_frames = 0;
			static uint64_t old_timestamp = 0;

			/* gps */
			hil_gps.timestamp_position = gps.time_usec;
//			hil_gps.counter = hil_counter++;
			hil_gps.time_gps_usec = gps.time_usec;
			hil_gps.lat = gps.lat;
			hil_gps.lon = gps.lon;
			hil_gps.alt = gps.alt;
//			hil_gps.counter_pos_valid = hil_counter++;
			hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m
			hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m
			hil_gps.s_variance_m_s = 100; // XXX 100 m/s variance?
			hil_gps.p_variance_m = 100; // XXX 100 m variance?
			hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s
			hil_gps.vel_n_m_s = (float)gps.vel * 1e-2f * cosf(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
			hil_gps.vel_e_m_s = (float)gps.vel * 1e-2f * sinf(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
			hil_gps.vel_d_m_s = 0.0f;
			hil_gps.cog_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f; // from deg*100 to rad
			hil_gps.fix_type = gps.fix_type;
			hil_gps.satellites_visible = gps.satellites_visible;

			/* publish */
			orb_publish(ORB_ID(vehicle_gps_position), pub_hil_gps, &hil_gps);

			// increment counters
			hil_counter += 1 ;
			hil_frames += 1 ;

			// output
			if ((timestamp - old_timestamp) > 10000000) {
				printf("receiving hil gps at %d hz\n", hil_frames/10);
				old_timestamp = timestamp;
				hil_frames = 0;
			}
		}

		if (msg->msgid == MAVLINK_MSG_ID_RAW_PRESSURE) {

			mavlink_raw_pressure_t press;
			mavlink_msg_raw_pressure_decode(msg, &press);

			/* packet counter */
			static uint16_t hil_counter = 0;
			static uint16_t hil_frames = 0;
			static uint64_t old_timestamp = 0;

			/* sensors general */
			hil_sensors.timestamp = press.time_usec;

			/* baro */

			float tempC =  press.temperature / 100.0f;
			float tempAvgK = T0 + (tempC + ground_tempC) / 2.0f;
			float h =  ground_alt + (R / g) * tempAvgK * logf(ground_press / press.press_abs);
			hil_sensors.baro_counter = hil_counter;
			hil_sensors.baro_pres_mbar = press.press_abs;
			hil_sensors.baro_alt_meter = h;
			hil_sensors.baro_temp_celcius = tempC;

			/* publish */
			orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors);

			// increment counters
			hil_counter += 1 ;
			hil_frames += 1 ;

			// output
			if ((timestamp - old_timestamp) > 10000000) {
				printf("receiving hil pressure at %d hz\n", hil_frames/10);
				old_timestamp = timestamp;
				hil_frames = 0;
			}
		}

		if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE) {

			mavlink_hil_state_t hil_state;
			mavlink_msg_hil_state_decode(msg, &hil_state);

			/* Calculate Rotation Matrix */
			//TODO: better clarification which app does this, atm we have a ekf for quadrotors which does this, but there is no such thing if fly in fixed wing mode

			if (mavlink_system.type == MAV_TYPE_FIXED_WING) {
				//TODO: assuming low pitch and roll values for now
				hil_attitude.R[0][0] = cosf(hil_state.yaw);
				hil_attitude.R[0][1] = sinf(hil_state.yaw);
				hil_attitude.R[0][2] = 0.0f;

				hil_attitude.R[1][0] = -sinf(hil_state.yaw);
				hil_attitude.R[1][1] = cosf(hil_state.yaw);
				hil_attitude.R[1][2] = 0.0f;

				hil_attitude.R[2][0] = 0.0f;
				hil_attitude.R[2][1] = 0.0f;
				hil_attitude.R[2][2] = 1.0f;

				hil_attitude.R_valid = true;
			}

			hil_global_pos.lat = hil_state.lat;
			hil_global_pos.lon = hil_state.lon;
			hil_global_pos.alt = hil_state.alt / 1000.0f;
			hil_global_pos.vx = hil_state.vx / 100.0f;
			hil_global_pos.vy = hil_state.vy / 100.0f;
			hil_global_pos.vz = hil_state.vz / 100.0f;


			/* set timestamp and notify processes (broadcast) */
			hil_global_pos.timestamp = hrt_absolute_time();
			orb_publish(ORB_ID(vehicle_global_position), pub_hil_global_pos, &hil_global_pos);

			hil_attitude.roll = hil_state.roll;
			hil_attitude.pitch = hil_state.pitch;
			hil_attitude.yaw = hil_state.yaw;
			hil_attitude.rollspeed = hil_state.rollspeed;
			hil_attitude.pitchspeed = hil_state.pitchspeed;
			hil_attitude.yawspeed = hil_state.yawspeed;

			/* set timestamp and notify processes (broadcast) */
			hil_attitude.timestamp = hrt_absolute_time();
			orb_publish(ORB_ID(vehicle_attitude), pub_hil_attitude, &hil_attitude);
		}

		if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
			mavlink_manual_control_t man;
			mavlink_msg_manual_control_decode(msg, &man);

			struct rc_channels_s rc_hil;
			memset(&rc_hil, 0, sizeof(rc_hil));
			static orb_advert_t rc_pub = 0;

			rc_hil.timestamp = hrt_absolute_time();
			rc_hil.chan_count = 4;

			rc_hil.chan[0].scaled = man.x / 1000.0f;
			rc_hil.chan[1].scaled = man.y / 1000.0f;
			rc_hil.chan[2].scaled = man.r / 1000.0f;
			rc_hil.chan[3].scaled = man.z / 1000.0f;

			struct manual_control_setpoint_s mc;
			static orb_advert_t mc_pub = 0;

			int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));

			/* get a copy first, to prevent altering values that are not sent by the mavlink command */
			orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &mc);

			mc.timestamp = rc_hil.timestamp;
			mc.roll = man.x / 1000.0f;
			mc.pitch = man.y / 1000.0f;
			mc.yaw = man.r / 1000.0f;
			mc.throttle = man.z / 1000.0f;

			/* fake RC channels with manual control input from simulator */


			if (rc_pub == 0) {
				rc_pub = orb_advertise(ORB_ID(rc_channels), &rc_hil);

			} else {
				orb_publish(ORB_ID(rc_channels), rc_pub, &rc_hil);
			}

			if (mc_pub == 0) {
				mc_pub = orb_advertise(ORB_ID(manual_control_setpoint), &mc);

			} else {
				orb_publish(ORB_ID(manual_control_setpoint), mc_pub, &mc);
			}
		}
	}
}
Beispiel #11
0
void MAVLinkSetMode(mavlink_message_t* handle_msg) // MAVLINK_MSG_ID_SET_MODE:
{
	mavlink_set_mode_t packet;

	DPRINT("MAVLINK_MSG_ID_SET_MODE %u\r\n", handle_msg->msgid);
	// send_text((uint8_t*) "Action: Specific Action Required\r\n");
	// decode
	mavlink_msg_set_mode_decode(handle_msg, &packet);
//	if (mavlink_check_target(packet.target_system, packet.target_component) == false) break;
	{
		switch (packet.base_mode)
		{
			case 192: // Manual
				DPRINT("Manual %u\r\n", packet.base_mode);
				break;
			case 208: // Manual/Stabilised
				DPRINT("Manual/Stabilised %u\r\n", packet.base_mode);
				break;
			case 216: // Manual/Guided
				DPRINT("Manual/Guided %u\r\n", packet.base_mode);
				break;
			case 156: // Auto
				DPRINT("Auto %u\r\n", packet.base_mode);
				break;
			case 65: // Disarm System
				DPRINT("Disarm System %u\r\n", packet.base_mode);
				break;
/*
			case MAV_ACTION_LAUNCH:
				//send_text((uint8_t*) "Action: Launch !\r\n");
				//DPRINT("Action: Launch !\r\n");
				//set_mode(TAKEOFF);
				break;
			case MAV_ACTION_RETURN:
				//send_text((uint8_t*) "Action: Return !\r\n");
				//DPRINT("Action: Return !\r\n");
				//set_mode(RTL);
				break;
			case MAV_ACTION_EMCY_LAND:
				//send_text((uint8_t*) "Action: Emergency Land !\r\n");
				//DPRINT("Action: Emergency Land !\r\n");
				//set_mode(LAND);
				break;
			case MAV_ACTION_HALT:
				//send_text((uint8_t*) "Action: Halt !\r\n");
				//DPRINT("Action: Halt !\r\n");
				//loiter_at_location();
				break;
			case MAV_ACTION_MOTORS_START:
			case MAV_ACTION_CONFIRM_KILL:
			case MAV_ACTION_EMCY_KILL:
			case MAV_ACTION_MOTORS_STOP:
			case MAV_ACTION_SHUTDOWN:
				//set_mode(MANUAL);
				break;
			case MAV_ACTION_CONTINUE:
				//process_next_command();
				break;
			case MAV_ACTION_SET_MANUAL:
				//set_mode(MANUAL);
				break;
			case MAV_ACTION_SET_AUTO:
				//set_mode(AUTO);
				break;
			case MAV_ACTION_STORAGE_READ:
				//send_text((uint8_t*)"Action: Storage Read\r\n");
				//DPRINT("Action: Storage Read\r\n");
				break;
			case MAV_ACTION_STORAGE_WRITE:
				//send_text((uint8_t*)"Action: Storage Write\r\n");
				//DPRINT("Action: Storage Write\r\n");
				break;
			case MAV_ACTION_CALIBRATE_RC:
				//send_text((uint8_t*)"Action: Calibrate RC\r\n");
				//DPRINT("Action: Calibrate RC\r\n");
				break;
			case MAV_ACTION_CALIBRATE_GYRO:
			case MAV_ACTION_CALIBRATE_MAG:
			case MAV_ACTION_CALIBRATE_ACC:
			case MAV_ACTION_CALIBRATE_PRESSURE:
			case MAV_ACTION_REBOOT:
				//startup_IMU_ground();
				break;
			case MAV_ACTION_REC_START: break;
			case MAV_ACTION_REC_PAUSE: break;
			case MAV_ACTION_REC_STOP: break;
			case MAV_ACTION_TAKEOFF:
				//send_text((uint8_t*)"Action: Take Off !\r\n");
				//DPRINT("Action: Take Off !\r\n");
				//set_mode(TAKEOFF);
				break;
			case MAV_ACTION_NAVIGATE:
				// send_text((uint8_t*)"Action: Navigate !\r\n");
				// DPRINT("Action: Navigate !\r\n");
				//set_mode(AUTO);
				break;
			case MAV_ACTION_LAND:
				//set_mode(LAND);
				break;
			case MAV_ACTION_LOITER:
				//set_mode(LOITER);
				break;
 */
			default:
				DPRINT("action: Specific Action Required %u\r\n", packet.base_mode);
				break;
		}
	}
}
/**
 * Telemetry transmit task. Processes queue events and periodic updates.
 */
static void telemetryRxTask(void *parameters)
{
	uint32_t inputPort;
	uint8_t	c;

	// Task loop
	while (1) {
#if defined(PIOS_INCLUDE_USB_HID)
		// Determine input port (USB takes priority over telemetry port)
		if (PIOS_USB_HID_CheckAvailable(0)) {
			inputPort = PIOS_COM_TELEM_USB;
		} else
#endif /* PIOS_INCLUDE_USB_HID */
		{
			inputPort = telemetryPort;
		}

		mavlink_channel_t mavlink_chan = MAVLINK_COMM_0;

		// Block until a byte is available
		PIOS_COM_ReceiveBuffer(inputPort, &c, 1, portMAX_DELAY);

		// And process it

		if (mavlink_parse_char(mavlink_chan, c, &rx_msg, &rx_status))
		{

			// Handle packet with waypoint component
			mavlink_wpm_message_handler(&rx_msg);

			// Handle packet with parameter component
			mavlink_pm_message_handler(mavlink_chan, &rx_msg);

			switch (rx_msg.msgid)
			{
			case MAVLINK_MSG_ID_HEARTBEAT:
			{
				// Check if this is the gcs
				mavlink_heartbeat_t beat;
				mavlink_msg_heartbeat_decode(&rx_msg, &beat);
				if (beat.type == MAV_TYPE_GCS)
				{
					// Got heartbeat from the GCS, we're good!
					lastOperatorHeartbeat = xTaskGetTickCount() * portTICK_RATE_MS;
				}
			}
			break;
			case MAVLINK_MSG_ID_SET_MODE:
			{
				mavlink_set_mode_t mode;
				mavlink_msg_set_mode_decode(&rx_msg, &mode);
				// Check if this system should change the mode
				if (mode.target_system == mavlink_system.sysid)
				{
					FlightStatusData flightStatus;
					FlightStatusGet(&flightStatus);

					switch (mode.base_mode)
					{
					case MAV_MODE_MANUAL_ARMED:
					{
						flightStatus.FlightMode = FLIGHTSTATUS_FLIGHTMODE_MANUAL;
						flightStatus.Armed = FLIGHTSTATUS_ARMED_ARMED;
					}
					break;
					case MAV_MODE_MANUAL_DISARMED:
					{
						flightStatus.FlightMode = FLIGHTSTATUS_FLIGHTMODE_MANUAL;
						flightStatus.Armed = FLIGHTSTATUS_ARMED_DISARMED;
					}
					break;
					case MAV_MODE_PREFLIGHT:
					{
						flightStatus.Armed = FLIGHTSTATUS_ARMED_DISARMED;
					}
					break;
					case MAV_MODE_STABILIZE_ARMED:
					{
						flightStatus.FlightMode = FLIGHTSTATUS_FLIGHTMODE_STABILIZED1;
						flightStatus.Armed = FLIGHTSTATUS_ARMED_ARMED;
					}
					break;
					case MAV_MODE_GUIDED_ARMED:
					{
						flightStatus.FlightMode = FLIGHTSTATUS_FLIGHTMODE_STABILIZED2;
						flightStatus.Armed = FLIGHTSTATUS_ARMED_ARMED;
					}
					break;
					case MAV_MODE_AUTO_ARMED:
					{
						flightStatus.FlightMode = FLIGHTSTATUS_FLIGHTMODE_STABILIZED3;
						flightStatus.Armed = FLIGHTSTATUS_ARMED_ARMED;
					}
					break;
					}

					bool newHilEnabled = (mode.base_mode & MAV_MODE_FLAG_DECODE_POSITION_HIL);
					if (newHilEnabled != hilEnabled)
					{
						if (newHilEnabled)
						{
							// READ-ONLY flag write to ActuatorCommand
							UAVObjMetadata meta;
							UAVObjHandle handle = ActuatorCommandHandle();
							UAVObjGetMetadata(handle, &meta);
							meta.access = ACCESS_READONLY;
							UAVObjSetMetadata(handle, &meta);

							mavlink_missionlib_send_gcs_string("ENABLING HIL SIMULATION");
							mavlink_missionlib_send_gcs_string("+++++++++++++++++++++++");
							mavlink_missionlib_send_gcs_string("BLOCKING ALL ACTUATORS");
						}
						else
						{
							// READ-ONLY flag write to ActuatorCommand
							UAVObjMetadata meta;
							UAVObjHandle handle = ActuatorCommandHandle();
							UAVObjGetMetadata(handle, &meta);
							meta.access = ACCESS_READWRITE;
							UAVObjSetMetadata(handle, &meta);

							mavlink_missionlib_send_gcs_string("DISABLING HIL SIMULATION");
							mavlink_missionlib_send_gcs_string("+++++++++++++++++++++++");
							mavlink_missionlib_send_gcs_string("ACTIVATING ALL ACTUATORS");
						}
					}
					hilEnabled = newHilEnabled;

					FlightStatusSet(&flightStatus);

					// Check HIL
					bool hilEnabled = (mode.base_mode & MAV_MODE_FLAG_DECODE_POSITION_HIL);
					enableHil(hilEnabled);
				}
			}
			break;
			case MAVLINK_MSG_ID_HIL_STATE:
			{
				if (hilEnabled)
				{
					mavlink_hil_state_t hil;
					mavlink_msg_hil_state_decode(&rx_msg, &hil);

					// Write GPSPosition
					GPSPositionData gps;
					GPSPositionGet(&gps);
					gps.Altitude = hil.alt/10;
					gps.Latitude = hil.lat/10;
					gps.Longitude = hil.lon/10;
					GPSPositionSet(&gps);

					// Write PositionActual
					PositionActualData pos;
					PositionActualGet(&pos);
					// FIXME WRITE POSITION HERE
					PositionActualSet(&pos);

					// Write AttitudeActual
					AttitudeActualData att;
					AttitudeActualGet(&att);
					att.Roll = hil.roll;
					att.Pitch = hil.pitch;
					att.Yaw = hil.yaw;
					// FIXME
					//att.RollSpeed = hil.rollspeed;
					//att.PitchSpeed = hil.pitchspeed;
					//att.YawSpeed = hil.yawspeed;

					// Convert to quaternion formulation
					RPY2Quaternion(&attitudeActual.Roll, &attitudeActual.q1);
					// Write AttitudeActual
					AttitudeActualSet(&att);

					// Write AttitudeRaw
					AttitudeRawData raw;
					AttitudeRawGet(&raw);
					raw.gyros[0] = hil.rollspeed;
					raw.gyros[1] = hil.pitchspeed;
					raw.gyros[2] = hil.yawspeed;
					raw.accels[0] = hil.xacc;
					raw.accels[1] = hil.yacc;
					raw.accels[2] = hil.zacc;
					//				raw.magnetometers[0] = hil.xmag;
					//				raw.magnetometers[0] = hil.ymag;
					//				raw.magnetometers[0] = hil.zmag;
					AttitudeRawSet(&raw);
				}
			}
			break;
			case MAVLINK_MSG_ID_COMMAND_LONG:
			{
				// FIXME Implement
			}
			break;
			}
		}
	}
}