Exemplo n.º 1
0
    void sci_mavlinkHilState(scicos_block *block, scicos::enumScicosFlags flag)
    {

        // data
        double * u=GetRealInPortPtrs(block,1);
        double * y=GetRealOutPortPtrs(block,1);
        int * ipar=block->ipar;

        static char * device;
        static int baudRate;
        static char ** stringArray;
        static int * intArray;
        static int count = 0;

        static uint16_t packet_drops = 0;

        //handle flags
        if (flag==scicos::initialize || flag==scicos::reinitialize)
        {
            if (mavlink_comm_0_port == NULL)
            {
                getIpars(1,1,ipar,&stringArray,&intArray);
                device = stringArray[0];
                baudRate = intArray[0];
                try
                {
                    mavlink_comm_0_port = new BufferedAsyncSerial(device,baudRate);
                }
                catch(const boost::system::system_error & e)
                {
                    Coserror((char *)e.what());
                }
            }
        }
        else if (flag==scicos::terminate)
        {
            if (mavlink_comm_0_port)
            {
                delete mavlink_comm_0_port;
                mavlink_comm_0_port = NULL;
            }
        }
        else if (flag==scicos::updateState)
        {
        }
        else if (flag==scicos::computeDeriv)
        {
        }
        else if (flag==scicos::computeOutput)
        {
            // channel
            mavlink_channel_t chan = MAVLINK_COMM_0;

			// loop rates
			// TODO: clean this up to use scicos events w/ timers
            static int attitudeRate = 50;
            static int positionRate = 10;
            static int airspeedRate = 1;

			// initial times
            double scicosTime = get_scicos_time();
            static double attitudeTimeStamp = scicosTime;
            static double positionTimeStamp = scicosTime;
            static double  airspeedTimeStamp = scicosTime;

			// send airspeed message
            if (scicosTime - airspeedTimeStamp > 1.0/airspeedRate)
            {
                airspeedTimeStamp = scicosTime;

				// airspeed (true velocity m/s)
            	float Vt = u[0];
                //double rawPress = 1;
                //double airspeed = 1;

                //mavlink_msg_raw_pressure_send(chan,timeStamp,airspeed,rawPress,0);
            }
            else if (scicosTime  - airspeedTimeStamp < 0)
                airspeedTimeStamp = scicosTime;

            // send attitude message
            if (scicosTime - attitudeTimeStamp > 1.0/attitudeRate)
            {
                attitudeTimeStamp = scicosTime;

				// attitude states (rad)
				float roll = u[1];
				float pitch = u[2];
				float yaw = u[3];

				// body rates
				float rollRate = u[4];
				float pitchRate = u[5];
				float yawRate = u[6];

                mavlink_msg_attitude_send(chan,attitudeTimeStamp,roll,pitch,yaw,
						rollRate,pitchRate,yawRate);
            }
            else if (scicosTime  - attitudeTimeStamp < 0)
                attitudeTimeStamp = scicosTime;

 		            // send gps mesage
            if (scicosTime - positionTimeStamp > 1.0/positionRate)
            {
                positionTimeStamp = scicosTime;

                // gps
                double cog = u[7];
                double sog = u[8];
                double lat = u[9]*rad2deg;
                double lon = u[10]*rad2deg;
                double alt = u[11];

                //double rawPress = 1;
                //double airspeed = 1;

                mavlink_msg_gps_raw_send(chan,positionTimeStamp,1,lat,lon,alt,2,10,sog,cog);
                //mavlink_msg_raw_pressure_send(chan,timeStamp,airspeed,rawPress,0);
            }
            else if (scicosTime  - positionTimeStamp < 0)
                positionTimeStamp = scicosTime;

            // receive messages
            mavlink_message_t msg;
            mavlink_status_t status;

            while(comm_get_available(MAVLINK_COMM_0))
            {
                uint8_t c = comm_receive_ch(MAVLINK_COMM_0);

                // try to get new message
                if(mavlink_parse_char(MAVLINK_COMM_0,c,&msg,&status))
                {
                    switch(msg.msgid)
                    {
                    case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
                    {
						//std::cout << "receiving messages" << std::endl;
        				mavlink_rc_channels_scaled_t rc_channels;
                        mavlink_msg_rc_channels_scaled_decode(&msg,&rc_channels);
                        y[0] = rc_channels.chan1_scaled/10000.0f;
                        y[1] = rc_channels.chan2_scaled/10000.0f;
                        y[2] = rc_channels.chan3_scaled/10000.0f;
                        y[3] = rc_channels.chan4_scaled/10000.0f;
                        y[4] = rc_channels.chan5_scaled/10000.0f;
                        y[5] = rc_channels.chan6_scaled/10000.0f;
                        y[6] = rc_channels.chan7_scaled/10000.0f;
                        y[7] = rc_channels.chan8_scaled/10000.0f;
                        break;
                    }
                }

                // update packet drop counter
                packet_drops += status.packet_rx_drop_count;
            }
        }
   	 }
  }
Exemplo n.º 2
0
/**
 * @brief Receive communication packets and handle them
 *
 * This function decodes packets on the protocol level and also handles
 * their value by calling the appropriate functions.
 */
void communication_receive(void)
{
	mavlink_message_t msg;
	mavlink_status_t status =
	{ 0 };
	status.packet_rx_drop_count = 0;

	// COMMUNICATION WITH ONBOARD COMPUTER

	while (uart0_char_available())
	{
		uint8_t c = uart0_get_char();


		if (global_data.state.uart0mode == UART_MODE_MAVLINK)
		{
			// Try to get a new message
			if (mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status))
			{
				// Handle message
				handle_mavlink_message(MAVLINK_COMM_0, &msg);
			}
		}
		else if (global_data.state.uart0mode == UART_MODE_BYTE_FORWARD)
		{
			uart1_transmit(c);
		}
		// And get the next one
	}

	// Update global packet drops counter
	global_data.comm.uart0_rx_drop_count += status.packet_rx_drop_count;
	global_data.comm.uart0_rx_success_count += status.packet_rx_success_count;
	status.packet_rx_drop_count = 0;

	// COMMUNICATION WITH EXTERNAL COMPUTER

	while (uart1_char_available())
	{
		uint8_t c = uart1_get_char();

		// Check if this link is used for MAVLink or GPS
		if (global_data.state.uart1mode == UART_MODE_MAVLINK)
		{
			//uart0_transmit((unsigned char)c);
			// Try to get a new message
			if (mavlink_parse_char(MAVLINK_COMM_1, c, &msg, &status))
			{
				// Handle message
				handle_mavlink_message(MAVLINK_COMM_1, &msg);
			}
		}
		else if (global_data.state.uart1mode == UART_MODE_GPS)
		{
			if (global_data.state.gps_mode == 10)
			{
				static uint8_t gps_i = 0;
				static char gps_chars[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN];
				if (c == '$' || gps_i == MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN
						- 1)
				{
					gps_i = 0;
					char gps_chars_buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN];
					strncpy(gps_chars_buf, gps_chars,
							MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
					debug_message_buffer(gps_chars_buf);

				}
				gps_chars[gps_i++] = c;
			}
			if (gps_parse(c))
			{
				// New GPS data received
				//debug_message_buffer("RECEIVED NEW GPS DATA");
				parse_gps_msg();

				if (gps_lat == 0)
				{
					global_data.state.gps_ok = 0;
					//debug_message_buffer("GPS Signal Lost");
				}
				else
				{
					global_data.state.gps_ok = 1;

					mavlink_msg_gps_raw_send(
							global_data.param[PARAM_SEND_DEBUGCHAN],
							sys_time_clock_get_unix_time(), gps_mode, gps_lat
									/ 1e7f, gps_lon / 1e7f, gps_alt / 100.0f,
							0.0f, 0.0f, gps_gspeed / 100.0f, gps_course / 10.0f);
				}
				//				// Output satellite info
				//				for (int i = 0; i < gps_nb_channels; i++)
				//				{
				//					mavlink_msg_gps_status_send(global_data.param[PARAM_SEND_DEBUGCHAN], gps_numSV, gps_svinfos[i].svid, gps_satellite_used(gps_svinfos[i].qi), gps_svinfos[i].elev, ((gps_svinfos[i].azim/360.0f)*255.0f), gps_svinfos[i].cno);
				//				}
			}

		}
		else if (global_data.state.uart1mode == UART_MODE_BYTE_FORWARD)
		{
			uart0_transmit(c);
			led_toggle(LED_YELLOW);
		}
		// And get the next one
	}

	// Update global packet drops counter
	global_data.comm.uart0_rx_drop_count += status.packet_rx_drop_count;
	global_data.comm.uart0_rx_success_count += status.packet_rx_success_count;
	status.packet_rx_drop_count = 0;
}
void MavlinkComm::sendMessage(uint8_t id, uint32_t param) {
    //_board->debug->printf_P(PSTR("send message\n"));

    // if number of channels exceeded return
    if (_channel == MAVLINK_COMM_3)
        return;

    uint64_t timeStamp = micros();

    switch (id) {

    case MAVLINK_MSG_ID_HEARTBEAT: {
        mavlink_msg_heartbeat_send(_channel, _board->getVehicle(),
                                   MAV_AUTOPILOT_ARDUPILOTMEGA);
        break;
    }

    case MAVLINK_MSG_ID_ATTITUDE: {
        mavlink_msg_attitude_send(_channel, timeStamp,
                                  _navigator->getRoll(), _navigator->getPitch(),
                                  _navigator->getYaw(), _navigator->getRollRate(),
                                  _navigator->getPitchRate(), _navigator->getYawRate());
        break;
    }

    case MAVLINK_MSG_ID_GLOBAL_POSITION: {
        mavlink_msg_global_position_send(_channel, timeStamp,
                                         _navigator->getLat() * rad2Deg,
                                         _navigator->getLon() * rad2Deg, _navigator->getAlt(),
                                         _navigator->getVN(), _navigator->getVE(),
                                         _navigator->getVD());
        break;
    }

    case MAVLINK_MSG_ID_LOCAL_POSITION: {
        mavlink_msg_local_position_send(_channel, timeStamp,
                _navigator->getPN(),_navigator->getPE(), _navigator->getPD(),
                _navigator->getVN(), _navigator->getVE(), _navigator->getVD());
        break;
    }

    case MAVLINK_MSG_ID_GPS_RAW: {
        mavlink_msg_gps_raw_send(_channel, timeStamp, _board->gps->status(),
                                 _board->gps->latitude/1.0e7,
                                 _board->gps->longitude/1.0e7, _board->gps->altitude/100.0, 0, 0,
                                 _board->gps->ground_speed/100.0,
                                 _board->gps->ground_course/10.0);
        break;
    }

    case MAVLINK_MSG_ID_GPS_RAW_INT: {
        mavlink_msg_gps_raw_send(_channel, timeStamp, _board->gps->status(),
                                 _board->gps->latitude,
                                 _board->gps->longitude, _board->gps->altitude*10.0, 0, 0,
                                 _board->gps->ground_speed/100.0,
                                 _board->gps->ground_course/10.0);
        break;
     }

    case MAVLINK_MSG_ID_SCALED_IMU: {
        int16_t xmag, ymag, zmag;
        xmag = ymag = zmag = 0;
        if (_board->compass) {
            // XXX THIS IS NOT SCALED
            xmag = _board->compass->mag_x;
            ymag = _board->compass->mag_y;
            zmag = _board->compass->mag_z;
        }
        mavlink_msg_scaled_imu_send(_channel, timeStamp,
            _navigator->getXAccel()*1e3,
            _navigator->getYAccel()*1e3,
            _navigator->getZAccel()*1e3,
            _navigator->getRollRate()*1e3,
            _navigator->getPitchRate()*1e3,
            _navigator->getYawRate()*1e3,
            xmag, ymag, zmag);
        break;
    }

    case MAVLINK_MSG_ID_RC_CHANNELS_SCALED: {
        int16_t ch[8];
        for (int i = 0; i < 8; i++)
            ch[i] = 0;
        for (uint8_t i = 0; i < 8 && i < _board->rc.getSize(); i++) {
            ch[i] = 10000 * _board->rc[i]->getPosition();
            //_board->debug->printf_P(PSTR("ch: %d position: %d\n"),i,ch[i]);
        }
        mavlink_msg_rc_channels_scaled_send(_channel, ch[0], ch[1], ch[2],
                                            ch[3], ch[4], ch[5], ch[6], ch[7], 255);
        break;
    }

    case MAVLINK_MSG_ID_RC_CHANNELS_RAW: {
        int16_t ch[8];
        for (int i = 0; i < 8; i++)
            ch[i] = 0;
        for (uint8_t i = 0; i < 8 && i < _board->rc.getSize(); i++)
            ch[i] = _board->rc[i]->getPwm();
        mavlink_msg_rc_channels_raw_send(_channel, ch[0], ch[1], ch[2],
                                         ch[3], ch[4], ch[5], ch[6], ch[7], 255);
        break;
    }

    case MAVLINK_MSG_ID_SYS_STATUS: {

        uint16_t batteryVoltage = 0; // (milli volts)
        uint16_t batteryPercentage = 1000; // times 10
        if (_board->batteryMonitor) {
            batteryPercentage = _board->batteryMonitor->getPercentage()*10;
            batteryVoltage = _board->batteryMonitor->getVoltage()*1000;
        }
        mavlink_msg_sys_status_send(_channel, _controller->getMode(),
                                    _guide->getMode(), _controller->getState(), _board->load * 10,
                                    batteryVoltage, batteryPercentage, _packetDrops);
        break;
    }

    case MAVLINK_MSG_ID_WAYPOINT_ACK: {
        sendText(SEVERITY_LOW, PSTR("waypoint ack"));
        //mavlink_waypoint_ack_t packet;
        uint8_t type = 0; // ok (0), error(1)
        mavlink_msg_waypoint_ack_send(_channel, _cmdDestSysId,
                                      _cmdDestCompId, type);

        // turn off waypoint send
        _receivingCmds = false;
        break;
    }

    case MAVLINK_MSG_ID_WAYPOINT_CURRENT: {
        mavlink_msg_waypoint_current_send(_channel,
                                          _guide->getCurrentIndex());
        break;
    }

    default: {
        char msg[50];
        sprintf(msg, "autopilot sending unknown command with id: %d", id);
        sendText(SEVERITY_HIGH, msg);
    }

    } // switch
} // send message