• Witaj na Forum Arduino Polska! Zapraszamy do rejestracji!
  • Znajdziesz tutaj wiele informacji na temat hardware / software.
Witaj! Logowanie Rejestracja


Ocena wątku:
  • 0 głosów - średnia: 0
  • 1
  • 2
  • 3
  • 4
  • 5
Mavlink biblioteka jak używać?
#11
Dobra już częściowo działające i współpracujące z open tx i flyplus. Tu sobie taki warsztacik zrobimy .
   
   
   
Kod:
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////TELEMETRIA MAVLINK/ARDUINO TO IBUS FLYSKU DO LUDKI ZANETOWEJ////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
#include  "mavlink.h"       //BIBLOTEKA MAVLINK  
#include <iBUSTelemetry.h>  //BIBLOTEKA IBUS
#define UPDATE_INTERVAL 500 //INTERWAŁ WYSLANIA IBUS
iBUSTelemetry telemetry(8); //PIN IBUS
uint32_t prevMillis = 0;    //CZAS MILIS
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////REJESTRY MAVLINK DO WYSLANIA IBUS///////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
int    Fix_type;          //RODZAJ FIX SAT
double Latitude;          //SZEROKOSC GPS
double Longitude;         //WYSOKOSC GPS
float  Speed;             //PREDKOSC M/S
int    Satellites_visible;//ILOSC SATELIT
int    Flight_mode;       //Flight_mode
float  Voltage_battery;   //NAPIECIE AKU
float  Current_battery;   //PRAD AKU
int    Heading;           //COMPASS
int    HDOP;              //HDOP
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////TEMPERATURA TO IBUS/////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////CZUJNIKI ZEWNETRZNE TEMPERATURY I REJESTRY////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
int PinTemp0 = A0 ;   //PIN TEMPERATURY1
int PinTemp1 = A1 ;   //PIN TEMPERATURY2
int PinTemp2 = A2 ;   //PIN TEMPERATURY3
int PinTemp3 = A3 ;   //PIN TEMPERATURY4
float temp0;          //
float temp1;          //ODCZYTANE TEMPERATURY
float temp2;          //
float temp3;          //WYLICZENIA DO NTC 10K WRAZIE POTRZEBY MODYFIKOWAC
float otemp0;         //PRZELICZONE NA NASZE
float otemp1;         //
float otemp2;         //
float otemp3;         //
float tempS;          // TEMPERATURA 2 SILNIKOW POKAZANIE WYZSZEJ
float tempR;          // TEMPERATURA 2 REGULATOROW POKAZANIE WYZSZEJ
//PARAMETRY NTC POTRZEBNE DO WYLICZENIA TEMPERATURY
#define RT0 10000   // Ω
#define B 3977      // K
#define VCC 5    //Supply voltage
#define R 10000  //R=10KΩ
float RT, VR, ln ;
float T0 = 298.15; //25 stopni w kelwinach
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////POMOCNICZE GPS DO DYSTANSU I PIAGORAS///////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
double  LatZ;         //SZEROKOSC GPS ZAPAMIETANA
double  LonZ;         //WYSOKOSC GPS ZAPAMIETANA                                            ////TU POMYSLEC JAK POBRAC Z APM//////
int     BlokG = 0;    //BLOKADA ZAPAMIETANIA GPS 0 PRZYJMUJE 1 ZAPISANA I ZABLOKOWANA
double  POS;          //WYLICZENIE ODLEGLOSCI
double  GPSdist;      //WYLICZONA ODLEGLOSC
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////WODA W LUDCE TO IBUS///////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
int PinWoda = 2 ;   //PIN ZALANIA WODA
int Woda;           //ZMIENNA WODA W LUDCE
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////KLAPY SPUSTOWE TO IBUS/////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
int PinKlapa1 = 3 ;   //PIN klapa1
int PinKlapa2 = 4 ;   //PIN klapa2
int Klapy;            //ZMIENNA KLAP
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////DEPPER ECHOSONDA/////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
int PinDepper = 5 ;   //PIN DEPPER STEROWANIE
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////KONFIGURACJA////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
void setup() {
pinMode(PinWoda,  INPUT_PULLUP); //PIN ZALANIA WODA PODCIAGNIETY DO PLUSA
pinMode(PinKlapa1,INPUT_PULLUP); //PIN KLAPY1 PODCIAGNIETY DO PLUSA         CZUJMIKO I/0
pinMode(PinKlapa2,INPUT_PULLUP); //PIN KLAPY2 PODCIAGNIETY DO PLUSA
pinMode(PinDepper,OUTPUT);       //PIN STEROWANIE DEPPER            
Serial.begin(57600);             //UART PC
Serial1.begin(57600);            //UART MAVLINK
request_datastream();            //NIE WIEM COS WYSYLA RAZ
telemetry.begin();               //URUCHOMIE IBUS
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////CZUJNIKI IBUS////////////////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
telemetry.addSensor(IBUS_MEAS_TYPE_GPS_STATUS);   // STATUS GPS I ILOSC SATELIT
telemetry.addSensor(IBUS_MEAS_TYPE_GPS_LAT);      // SZEROKOSC GEO
telemetry.addSensor(IBUS_MEAS_TYPE_GPS_LON);      // DLUGOSC GEO
telemetry.addSensor(IBUS_MEAS_TYPE_GROUND_SPEED); // PREDKOSC M/S GPS
telemetry.addSensor(IBUS_MEAS_TYPE_FLIGHT_MODE);  // FLIGHT MODE
telemetry.addSensor(IBUS_MEAS_TYPE_EXTV);         // NAPIECIE AKUMULATORA
telemetry.addSensor(IBUS_MEAS_TYPE_BAT_CURR);     // PRĄD AKUMULATORA
telemetry.addSensor(IBUS_MEAS_TYPE_TEM);          // TEMPERATURA SILNIKA
telemetry.addSensor(IBUS_MEAS_TYPE_TEM);          // TEMPERATURA MOSTKA H
telemetry.addSensor(IBUS_MEAS_TYPE_CMP_HEAD);     // KOMPAS 0 TO POLNOC
telemetry.addSensor(IBUS_MEAS_TYPE_COG);          // HDOP
telemetry.addSensor(IBUS_MEAS_TYPE_GPS_DIST);     // DYSTANS NIE WIEM JAK BOBRAC Z APM NARZAZIE WYLICZONY
telemetry.addSensor(0x85);
telemetry.addSensor(0x86);
}
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////PROGRAM GLUWNY/////////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
void loop() {        
MavLink_receive();
czujniki(); 
updateValues();
telemetry.run();
}
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////ODBIERA BICIE SERCA I GPS ZERZNIETE Z TUTKOW//////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
void MavLink_receive()
  {
  mavlink_message_t msg;
  mavlink_status_t status;

  while(Serial1.available())
  {
    uint8_t c= Serial1.read();

    //Get new message
    if(mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status))
    {

    //Handle new message from autopilot
      switch(msg.msgid)
      {

        case MAVLINK_MSG_ID_GPS_RAW_INT:
      {
        mavlink_gps_raw_int_t packet;
        mavlink_msg_gps_raw_int_decode(&msg, &packet);
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////ODEBRANIE/WYSLANIE DO REJESTRU///////////////////////////////////////////////////////////////////////   
          Fix_type = packet.fix_type;
          Latitude = packet.lat;
          Longitude = packet.lon;
          //Alt = packet.alt;
          Speed = packet.vel;
          Satellites_visible = packet.satellites_visible;
          HDOP = packet.eph;
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////       
      }
      break;
       case MAVLINK_MSG_ID_HEARTBEAT:
       {
       mavlink_heartbeat_t hb;
       mavlink_msg_heartbeat_decode(&msg,&hb);
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////ODEBRANIE/WYSLANIE DO REJESTRU////////////////////////////////////////////////////////////////////////      
          Flight_mode = hb.custom_mode;
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////     
      }
      break;
      case MAVLINK_MSG_ID_SYS_STATUS:  // #1: SYS_STATUS
      {
        mavlink_sys_status_t sys_status;
        mavlink_msg_sys_status_decode(&msg, &sys_status);
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////ODEBRANIE/WYSLANIE DO REJESTRU///////////////////////////////////////////////////////////////////////////// 
        Voltage_battery = sys_status.voltage_battery;
        Current_battery = sys_status.current_battery;
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
}
break;
case MAVLINK_MSG_ID_VFR_HUD:
    {
      mavlink_vfr_hud_t packet;
      mavlink_msg_vfr_hud_decode(&msg, &packet);
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////ODEBRANIE/WYSLANIE DO REJESTRU////////////////////////////////////////////////////////////////////////////////     
      Heading = packet.heading;
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////           
    }
    break;          
      } 
    }
  }
}
//////////////////////////////////////////////////////////TU COS WYSYLA MAWLINK RAZ////////////////////////////////////////////////////////////////////////////////
void request_datastream() {
//Request Data from Pixhawk
  uint8_t _system_id = 255; // id of computer which is sending the command (ground control software has id of 255)
  uint8_t _component_id = 2; // seems like it can be any # except the number of what Pixhawk sys_id is
  uint8_t _target_system = 1; // Id # of Pixhawk (should be 1)
  uint8_t _target_component = 0; // Target component, 0 = all (seems to work with 0 or 1
  uint8_t _req_stream_id = MAV_DATA_STREAM_ALL;
  uint16_t _req_message_rate = 0x01; //number of times per second to request the data in hex
  uint8_t _start_stop = 1; //1 = start, 0 = stop

  mavlink_message_t msg;
  uint8_t buf[MAVLINK_MAX_PACKET_LEN];

  // Pack the message
  mavlink_msg_request_data_stream_pack(_system_id, _component_id, &msg, _target_system, _target_component, _req_stream_id, _req_message_rate, _start_stop);
  uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);  // Send the message (.write sends as bytes)

  Serial1.write(buf, len);//Write data to serial port
}

///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////MOJE CZUJNIKI///////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
void czujniki()
{
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// 
/////////////////////////////////////////////////////////////////ODCZYT PIN ANALOGOWYCH TEMP///////////////////////////////////////////////////////////////////////////
temp0 = analogRead(PinTemp0);             
temp1 = analogRead(PinTemp1);
temp2 = analogRead(PinTemp2);
temp3 = analogRead(PinTemp3); 
/////////////////////////////////////////////////////////PRZELICZENIE WARTOSCI ANALOG NA STOPNIE///////////////////////////////////////////////////////////////////////   
///////////////////czujnik temp0
  temp0 = (VCC / 1023.00) * temp0;     
  VR = VCC - temp0;
  RT = temp0 / (VR / R);              
  ln = log(RT / RT0);
  otemp0 = (1 / ((ln / B) + (1 / T0)));
  otemp0 = otemp0 - 273.15;                
//////////////czujnik temp1          
  temp1 = (VCC / 1023.00) * temp1;    
  VR = VCC - temp1;
  RT = temp1 / (VR / R);              
  ln = log(RT / RT0);
  otemp1 = (1 / ((ln / B) + (1 / T0)));
  otemp1 = otemp1 - 273.15;                
////////////////czujnik temp2       
  temp2 = (VCC / 1023.00) * temp2;    
  VR = VCC - temp2;
  RT = temp2 / (VR / R);             
  ln = log(RT / RT0);
  otemp2 = (1 / ((ln / B) + (1 / T0)));
  otemp2 = otemp2 - 273.15;               
/////////////////czujnik temp3             
  temp3 = (VCC / 1023.00) * temp3;     
  VR = VCC - temp3;
  RT = temp3 / (VR / R);              
  ln = log(RT / RT0);
  otemp3 = (1 / ((ln / B) + (1 / T0)));
  otemp3 = otemp3 - 273.15;
  ////////////////WYSLANIE WYZSZYCH WARTOSCI DO APARATURY
if (otemp0 > otemp1) {
    tempS = otemp0;
  }else{
    tempS = otemp1;
  }
if (otemp2 > otemp3) {
    tempR = otemp2;
  }else{
    tempR = otemp3;
  }
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////WODA W LUDCE////////////////////////////////////////////////////////////////////////////////////
if (digitalRead(PinWoda) == HIGH) {
    Woda = 0; //SUCHO W SKORUPIE
  }else{
    Woda = 1; //WODA W SKORUPIE
  }
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////KLAPY SPUSTOWE//////////////////////////////////////////////////////////////////////////////////
if ((digitalRead(PinKlapa1) == LOW)&&(digitalRead(PinKlapa2) == LOW)) {
    Klapy = 0; //KLAPY ZAMKNIETE
  }
if ((digitalRead(PinKlapa1) == HIGH)&&(digitalRead(PinKlapa2) == HIGH)) {
    Klapy = 3; //KLAPY OTWARTE
  }
if ((digitalRead(PinKlapa1) == HIGH)&&(digitalRead(PinKlapa2) == LOW)) {
    Klapy = 1; //KLAPA1 OTWARTA / KLAPA2 ZAMKNIETA
  }
if ((digitalRead(PinKlapa1) == LOW)&&(digitalRead(PinKlapa2) == HIGH)) {
    Klapy = 2; //KLAPA1 ZAMKNIETA / KLAPA2 OTWARTA
  }
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////    
//////////////////////////////////////////////////////////GPS ZAPAMIETAC I PITAGORAS DLA ODLEGLOSCI////////////////////////////////////////////////////////////////////
if ((Fix_type >= 3)&&(Satellites_visible >= 6)&&(BlokG == 0)) {
    LatZ = Latitude;
    LonZ = Longitude;
    BlokG = 1;
  }    
   POS =(((LatZ-Latitude)*(LatZ-Latitude))+((LonZ-Longitude)*(LonZ-Longitude))*73);
   GPSdist =sqrt(POS)/1000;
}
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////////STEROWANIE DEPPER////////////////////////////////////////////////////////////////////////////

//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////ILOSC PUNKTOW///////////////////////////////////////////////////////////////////////////////

//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////IBUS AKTUALIZACJA CZUJNIKOW/////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
void updateValues()
{
    uint32_t currMillis = millis();

    if (currMillis - prevMillis >= UPDATE_INTERVAL) { // Code in the middle of these brackets will be performed every 500ms.
        prevMillis = currMillis;

        telemetry.setSensorValue(1,telemetry.gpsStateValues(Fix_type,Satellites_visible));
        telemetry.setSensorValue(2,Latitude);
        telemetry.setSensorValue(3,Longitude);
        telemetry.setSensorValue(4,Speed);
        telemetry.setSensorValue(5,Flight_mode);                                                            
        telemetry.setSensorValueFP(6,Voltage_battery);
        telemetry.setSensorValueFP(7,Current_battery);
        telemetry.setSensorValueFP(8,tempS);
        telemetry.setSensorValueFP(9,tempR);
        telemetry.setSensorValue(10,Heading);
        telemetry.setSensorValue(11,HDOP);
        telemetry.setSensorValue(12,GPSdist);
        telemetry.setSensorValue(13,Klapy);
        telemetry.setSensorValue(14,Woda);
    }
}
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////


Na tej stronie znalazłem jak wysłać misje do APM
https://www.locarbftw.com/uploading-a-wa...g-mavlink/

A na tej jest metodą pobrania misji i w bibliotece są te pliki.
https://mavlink.io/en/services/mission.h...sion_types

Ten mavlink jest ciężki do zrozumienia , a to pomoże w odczycie ilości zapisanych punktów i poznamy pozycję domowa bo ona tam jest .
 
Odpowiedź
  


Wiadomości w tym wątku
Mavlink biblioteka jak używać? - przez Dzimi87 - 30-04-2023, 00:24
RE: Mavlink biblioteka jak używać? - przez Irvin - 30-04-2023, 17:14
RE: Mavlink biblioteka jak używać? - przez Dzimi87 - 30-04-2023, 21:55
RE: Mavlink biblioteka jak używać? - przez MarekT - 29-06-2023, 20:04
RE: Mavlink biblioteka jak używać? - przez MarekT - 29-06-2023, 20:06
RE: Mavlink biblioteka jak używać? - przez Irvin - 01-05-2023, 03:55
RE: Mavlink biblioteka jak używać? - przez Dzimi87 - 03-05-2023, 08:13
RE: Mavlink biblioteka jak używać? - przez Dzimi87 - 05-05-2023, 14:19
RE: Mavlink biblioteka jak używać? - przez Dzimi87 - 02-06-2023, 22:37
RE: Mavlink biblioteka jak używać? - przez Dzimi87 - 05-06-2023, 01:49
RE: Mavlink biblioteka jak używać? - przez Dzimi87 - 08-06-2023, 09:24
RE: Mavlink biblioteka jak używać? - przez Dzimi87 - 23-06-2023, 15:18
RE: Mavlink biblioteka jak używać? - przez Dzimi87 - 02-07-2023, 08:47

Skocz do:


Przeglądający: 1 gości