PETRONE / BLE / Protocol / Structs
Modified : 2017.10.18


데이터 송수신 시에 사용하는 구조체들을 소개합니다.



Protocol::Ack

Data that PETRONE sends in a response when it receives data. Returns the internal time of PETRONE and the type of data received. Replies most commands except Ack and Control.

namespace Protocol
{
    struct Ack
    {
        u32  systemTime;    // receive time
        u8   dataType;      // receive datatype
    };
}



Protocol::Request

Used to request data to PETRONE.

namespace Protocol
{
    struct Request
    {
        u8   dataType;     // request datatype
    };
}



Protocol::Control

Used to control data to PETRONE.

namespace Protocol
{
    struct Control
    {
        s8   roll;        // Roll
        s8   pitch;       // Pitch
        s8   yaw;         // Yaw
        s8   throttle;    // Throttle
    };
}

Control input values are in the range :

  • Drive mode used only throttle(Forward-Backward) and roll(Left-Right)
Name Type Range Direction Minus(-) Plus(+)
roll s8 -100 ~ 100 Left-Right Left Right
pitch s8 -100 ~ 100 Forward-Backward Backward Forward
yaw s8 -100 ~ 100 Turn Left-Right Counterclockwise Clockwise
throttle s8 -100 ~ 100 Up-Down Down Up



Protocol::Command

Send one command

namespace Protocol
{
    struct Command
    {
        CommandBase   command;
    };
}



Protocol::Command2

Send two command

namespace Protocol
{
    struct Command2
    {
        CommandBase   command1;
        CommandBase   command2;
    };
}



Protocol::Command3

Send three command

namespace Protocol
{
    struct Command3
    {
        CommandBase   command1;
        CommandBase   command2;
        CommandBase   command3;
    };
}



Protocol::Address

Return BLE address

namespace Protocol
{
    struct Address
    {
        u8   address[6];
    };
}



Protocol::State

Return PETRONE state

namespace Protocol
{
    struct State
    {
        u8          modeVehicle;        // Vehicle mode
        
        u8          modeSystem;         // System mode 
        u8          modeFlight;         // Flight mode 
        u8          modeDrive;          // Drive mode 
        
        u8          sensorOrientation;  // Sensor Orientation
        u8          coordinate;         // Headless mode 
        u8          battery;            // Drone battery(0 ~ 100)
    };
}



Protocol::Attitude

Drone Attitude

namespace Protocol
{
    struct Attitude
    {
        s16          roll;         // Roll
        s16          pitch;        // Pitch
        s16          yaw;          // Yaw
    };
}

The drones's attitude range of use is as follows :

Name Type Range Description
roll s16 -180 ~ 180 Angle of left-right
pitch s16 -180 ~ 180 Angle of forward-backward
yaw s16 0 ~ 360 Angle of gravity rotated axis

Sensor data value range is follows :

Name Type Range
roll s16 -32768 ~ 32767
pitch s16 -32768 ~ 32767
yaw s16 -32768 ~ 32767



Protocol::GyroBias

Retruns gyro bias value.

namespace Protocol
{
    struct GyroBias
    {
        s16          roll;         // Roll
        s16          pitch;        // Pitch
        s16          yaw;          // Yaw
    };
}



Protocol::TrimFlight

Flight mode trim setting protocol.

namespace Protocol
{
    struct TrimFlight
    {
        s16          roll;         // Roll
        s16          pitch;        // Pitch
        s16          yaw;          // Yaw
        s16          throttle;     // Throttle
    };
}



Protocol::TrimDrive

Drive mode trim setting protocol.

namespace Protocol
{
    struct TrimDrive
    {
        s16          wheel;         // Wheel
    };
}



Protocol::TrimAll

All trim setting once.

namespace Protocol
{
    struct TrimAll
    {
        TrimFlight   flight;
        TrimDrive    drive;
    };
}



Protocol::CountFlight

Use to read the stored flight log.

namespace Protocol
{
    struct CountFlight
    {
        u32     timeFlight;             // Flight time
        
        u16     countTakeOff;           // count of Takeoff
        u16     countLanding;           // count of Landing
        u16     countAccident;          // count of Accident
    };
}



Protocol::CountDrive

Use to read the stored drive log.

namespace Protocol
{
    struct CountDrive
    {
        u32     timeDrive;              // Drive time
        
        u16     countAccident;          // count of Accident
    };
}

countAccident variable make for count of accident. But count may also increase due to the impact of uneven road surfaces during actual driving. Consider it meaningless at this time.



Protocol::IrMessage

Data that is used to transfer IR data or sent to an external device when IR data is receive by PETRONE

namespace Protocol
{
    struct IrMessage
    {
        u8  direction;               // Receive direction
        u32 irData;                  // IR message
    };
}



Protocol::ImuRawAndAngle

Returns the value of the gyro sensor and the attitude value of the drone.

namespace Protocol
{
    struct ImuRawAndAngle
    {
        s16     accX;
        s16     accY;
        s16     accZ;
        s16     gyroRoll;
        s16     gyroPitch;
        s16     gyroYaw;
        s16     angleRoll;
        s16     anglePitch;
        s16     angleYaw;
    };
}



Protocol::Pressure

Retruns pressure sensor. d1 and d2 is output only MS5607. DPS310 use device return only 0.

namespace Protocol
{
    struct Pressure
    {
        s32		d1;
        s32		d2;
        s32		temperature;
        s32		pressure;
    };
}
  • Pressure output unit are in millimetres(mm).



Protocol::ImageFlow

Image optical flow calcurated axis position

namespace Protocol
{
    struct ImageFlow
    {
        s32		positionX;
        s32		positionY;
    };
}
  • positionX, positionYoutput unit are in millimetres(mm).



Protocol::Button

Drone button flag

namespace Protocol
{
    struct Button
    {
        u8      button;
    };
}



Protocol::Motor

Motor control and check current value

namespace Protocol
{
    struct Motor
    {
        MotorBase motor[4];
    };
}



Protocol::Range

Range sensor data If an additional sensor module is not installed, output only bottom value.

namespace Protocol
{
    struct Range
    {
        u16	left;
        u16	front;
        u16	right;
        u16	rear;
        u16	top;
        u16	bottom;
    };
}
  • All unit are in millimetres(mm).



Protocol::UpdateLookupTarget

Request firmware Information.
PETRONE has control MCU(Main) and communication MCU(sub). Protocol::UpdateLookupTarget used for request target MCU's Protocol::UpdateInformation

namespace Protocol
{
    struct UpdateLookupTarget
    {
        u32	deviceType;
    };
}



Protocol::UpdateInformation

Firmware Information
If PC or App send Protocol::UpdateLookupTarget, the device with the deviceType matches it, response Protocol::UpdateInformation.

namespace Protocol
{
    struct UpdateInformation
    {
        u8      modeUpdate;     // The progress of the update

        u32     deviceType;     // Device type
        u8      imageType;      // Firmware image type  
        u16     imageVersion;   // Firmware image version

        u8      year;           // Firmware build year
        u8      month;          // Firmware build month
        u8      day;            // Firmware build day
    };
}



Protocol::Update

Firmware update.
When updating the firmware, the file transfers data that is truncated to 16 bytes. There are no other responses during the Protocol::Update transfer. If a transfer failure occurs, drone sends Protocol::UpdateLocationCorrect. When you receive the packet, you can start sending it again from the block location you specified.

namespace Protocol
{
    struct Update
    {
        u16     indexBlock;         // Block index(16byte block index)
        u8      dataArray[16];      // data block
    };
}
  • indexBlock : The value divided by 16 from the actual location of the file.



Protocol::UpdateLocationCorrect

Correct Firmware Update Locations.
If the firmware update encounters a block that fails to transfer, send a request to send it again from indexBlockNext.

namespace Protocol
{
    struct UpdateLocationCorrect
    {
        u16     indexBlockNext;     // indexblock number
    };
}
  • indexBlockNext : The value divided by 16 from the actual location of the file.



PETRONE

  1. Intro
  2. Typedef
  3. DataType
  4. Definitions
  5. Base Structs
  6. Structs
  7. Structs - Light
  8. Firmware Update
  1. Intro
  2. DataType
  3. Definitions
  4. Structs
  5. Examples


Index