void GCS_MAVLINK::update(void (*run_cli)(AP_HAL::UARTDriver *)) { // receive new packets mavlink_message_t msg; mavlink_status_t status; status.packet_rx_drop_count = 0; // process received bytes uint16_t nbytes = comm_get_available(chan); for (uint16_t i=0; i<nbytes; i++) { uint8_t c = comm_receive_ch(chan); if (run_cli != NULL) { /* allow CLI to be started by hitting enter 3 times, if no * heartbeat packets have been received */ if (!mavlink_active && (hal.scheduler->millis() - _cli_timeout) < 20000 && comm_is_idle(chan)) { if (c == '\n' || c == '\r') { crlf_count++; } else { crlf_count = 0; } if (crlf_count == 3) { run_cli(_port); } } } // Try to get a new message if (mavlink_parse_char(chan, c, &msg, &status)) { // we exclude radio packets to make it possible to use the // CLI over the radio if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) { mavlink_active = true; } handleMessage(&msg); } } if (!waypoint_receiving) { return; } uint32_t tnow = hal.scheduler->millis(); uint32_t wp_recv_time = 1000U + (stream_slowdown*20); if (waypoint_receiving && waypoint_request_i <= waypoint_request_last && tnow - waypoint_timelast_request > wp_recv_time) { waypoint_timelast_request = tnow; send_message(MSG_NEXT_WAYPOINT); } // stop waypoint receiving if timeout if (waypoint_receiving && (tnow - waypoint_timelast_receive) > wp_recv_time+waypoint_receive_timeout) { waypoint_receiving = false; } }
void simplegcs_update(mavlink_channel_t chan) { mavlink_message_t msg; mavlink_status_t status; while(comm_get_available(chan)){ uint8_t c = comm_receive_ch(chan); bool newmsg = mavlink_parse_char(chan, c, &msg, &status); if (newmsg) { handle_message(chan, &msg); } } }
uint8_t AP_InertialSensor_UserInteract_MAVLink::blocking_read(void) { uint32_t start_ms = hal.scheduler->millis(); /* Wait for a COMMAND_ACK message to be received from the ground station */ while (hal.scheduler->millis() - start_ms < 30000U) { while (!comm_get_available(_chan)) { hal.scheduler->delay(1); } uint8_t c = comm_receive_ch(_chan); mavlink_message_t msg; mavlink_status_t status; if (mavlink_parse_char(_chan, c, &msg, &status)) { if (msg.msgid == MAVLINK_MSG_ID_COMMAND_ACK) { return 0; } } } hal.console->println_P(PSTR("Timed out waiting for user response")); return 0; }
void MavlinkComm::receive() { //_board->debug->printf_P(PSTR("receive\n")); // if number of channels exceeded return // if (_channel == MAVLINK_COMM_3) return; // receive new packets mavlink_message_t msg; mavlink_status_t status; status.packet_rx_drop_count = 0; // process received bytes while (comm_get_available(_channel)) { uint8_t c = comm_receive_ch(_channel); // Try to get a new message if (mavlink_parse_char(_channel, c, &msg, &status)) _handleMessage(&msg); } // Update packet drops counter _packetDrops += status.packet_rx_drop_count; }
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; } } } }
void sci_mavlinkHilTracker(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_2_port == NULL) { getIpars(1,1,ipar,&stringArray,&intArray); device = stringArray[0]; baudRate = intArray[0]; try { mavlink_comm_2_port = new BufferedAsyncSerial(device,baudRate); } catch(const boost::system::system_error & e) { Coserror((char *)e.what()); } } } else if (flag==scicos::terminate) { if (mavlink_comm_2_port) { delete mavlink_comm_2_port; mavlink_comm_2_port = NULL; } } else if (flag==scicos::updateState) { } else if (flag==scicos::computeDeriv) { } else if (flag==scicos::computeOutput) { // channel mavlink_channel_t chan = MAVLINK_COMM_2; // loop rates // TODO: clean this up to use scicos events w/ timers static int positionRate = 10; // initial times double scicosTime = get_scicos_time(); static double positionTimeStamp = scicosTime; // send global position if (scicosTime - positionTimeStamp > 1.0/positionRate) { positionTimeStamp = scicosTime; // gps double lat = u[0]*rad2deg; double lon = u[1]*rad2deg; double alt = u[2]; double vN = u[3]; double vE = u[4]; double vD = u[5]; mavlink_msg_global_position_send(chan,positionTimeStamp,lat,lon,alt,vN,vE,vD); //std::cout << "sending global position" << std::endl; } else if (scicosTime - positionTimeStamp < 0) positionTimeStamp = scicosTime; // receive messages mavlink_message_t msg; mavlink_status_t status; while(comm_get_available(MAVLINK_COMM_2)) { //std::cout << "serial available" << std::endl; uint8_t c = comm_receive_ch(MAVLINK_COMM_2); // try to get new message if(mavlink_parse_char(MAVLINK_COMM_2,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; } } } }