Helper to return single bit of u32 data. This returns the "position"'th bit of the given u32,
assuming it is Zero indexed.
*/
u32read_bit(u32data,intposition){
return(data>>position)&1;
}
/*
This method is used to configure the bits within the flags struct by reading in the data sent from the user via the groundstation.
Params:
configData: Payload from configuration packet sent from the groundstation. Each bit (starting at 31, downto 10) represents a flag either being disabled (0) or enabled (1)
SensorRTFlags_t * flags: This contains a pointer to the flags struct. This struct is held within the quad's memory and is used to determine which information within the quad's sensors
will be sent back during each control loop. Due to the limited bandwidth capacity of the UART, it is undesirable to have a large amount of these flags enabled
when sending data.
Returns:
int size: Total number of data types desired to be displayed via flight data tool.
This method populates a payload full of sensor data and transmits it to the groundstation (for real-time data logging feature)
Params:
CommDriver *comm: This contains a pointer to the communication medium currently being used to communicate with the groundstation. In its current state, this will be
the UART capabilities located on the quad.
raw_sensor_t * data: This contains a pointer to the struct containing all of the current sensor data that has been collected by the various peripherals on the quad. This
will be used to populate the majority of the information within the payload packet.
SensorRTFlags_t * flags: This contains a pointer to the flags struct. This struct is held within the quad's memory and is used to determine which information within the sensors
will be sent back during each control loop. Due to the limited bandwidth capacity of the UART, it is undesirable to have a large amount of these flags
enabled when sending data. The exact contents of the flags struct are detailed in the process_configuration_packet method as well as the struct definition
within this file's header.
Returns:
bytes_sent: Total number of bytes that were transferred via the communication channel (UART). This number can be used to determine the succesful transfer of data.
//populate correct bit within flag_info. Due to the fact that enabled flags are stored only on the quad's memory, this information will need to be sent to the groundstation with every
//packet to ensure the correct formatting of data before being graphed.
flag_info|=QUAD_HEIGHT_FLAG;
}
//64-bit data must be sent in two concurrent 32 bit data blocks within the payload. The MSB's of the data are stored first, then the LSB's.