You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
107 lines
4.0 KiB
107 lines
4.0 KiB
4 years ago
|
/*
|
||
|
* UAVCAN data structure definition for libcanard.
|
||
|
*
|
||
|
* Autogenerated, do not edit.
|
||
|
*
|
||
|
* Source file: E:\000_MyProjects\UAVCAN\libcanard_zrzk_new\dsdl_compiler\zrzk\equipment\range_sensor\26110.Proximity.uavcan
|
||
|
*/
|
||
|
|
||
|
#ifndef __ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY
|
||
|
#define __ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY
|
||
|
|
||
|
#include <stdint.h>
|
||
|
#include "canard.h"
|
||
|
|
||
|
#ifdef __cplusplus
|
||
|
extern "C"
|
||
|
{
|
||
|
#endif
|
||
|
|
||
|
/******************************* Source text **********************************
|
||
|
uint8 sensor_id
|
||
|
|
||
|
uint5 SENSOR_TYPE_UNDEFINED = 0
|
||
|
uint5 SENSOR_TYPE_SONAR = 1
|
||
|
uint5 SENSOR_TYPE_LIDAR = 2
|
||
|
uint5 SENSOR_TYPE_RADAR = 3
|
||
|
uint5 sensor_type
|
||
|
|
||
|
uint3 READING_TYPE_UNDEFINED = 0 # Range is unknown
|
||
|
uint3 READING_TYPE_VALID_RANGE = 1 # Range field contains valid distance
|
||
|
uint3 READING_TYPE_TOO_CLOSE = 2 # Range field contains min range for the sensor
|
||
|
uint3 READING_TYPE_TOO_FAR = 3 # Range field contains max range for the sensor
|
||
|
uint3 reading_type
|
||
|
|
||
|
uint16 d0 # Meters distance_cm
|
||
|
uint16 d45
|
||
|
uint16 d90
|
||
|
uint16 d135
|
||
|
uint16 d180
|
||
|
uint16 d225
|
||
|
uint16 d270
|
||
|
uint16 d315
|
||
|
******************************************************************************/
|
||
|
|
||
|
/********************* DSDL signature source definition ***********************
|
||
|
zrzk.equipment.range_sensor.Proximity
|
||
|
saturated uint8 sensor_id
|
||
|
saturated uint5 sensor_type
|
||
|
saturated uint3 reading_type
|
||
|
saturated uint16 d0
|
||
|
saturated uint16 d45
|
||
|
saturated uint16 d90
|
||
|
saturated uint16 d135
|
||
|
saturated uint16 d180
|
||
|
saturated uint16 d225
|
||
|
saturated uint16 d270
|
||
|
saturated uint16 d315
|
||
|
******************************************************************************/
|
||
|
|
||
|
#define ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY_ID 26110
|
||
|
#define ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY_NAME "zrzk.equipment.range_sensor.Proximity"
|
||
|
#define ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY_SIGNATURE (0x92066602E96C261ULL)
|
||
|
|
||
|
#define ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY_MAX_SIZE ((144 + 7)/8)
|
||
|
|
||
|
// Constants
|
||
|
#define ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY_SENSOR_TYPE_UNDEFINED 0 // 0
|
||
|
#define ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY_SENSOR_TYPE_SONAR 1 // 1
|
||
|
#define ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY_SENSOR_TYPE_LIDAR 2 // 2
|
||
|
#define ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY_SENSOR_TYPE_RADAR 3 // 3
|
||
|
#define ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY_READING_TYPE_UNDEFINED 0 // 0
|
||
|
#define ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY_READING_TYPE_VALID_RANGE 1 // 1
|
||
|
#define ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY_READING_TYPE_TOO_CLOSE 2 // 2
|
||
|
#define ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY_READING_TYPE_TOO_FAR 3 // 3
|
||
|
|
||
|
typedef struct
|
||
|
{
|
||
|
uint16_t d0; // bit len 16
|
||
|
uint16_t d45; // bit len 16
|
||
|
uint16_t d90; // bit len 16
|
||
|
uint16_t d135; // bit len 16
|
||
|
uint16_t d180; // bit len 16
|
||
|
uint16_t d225; // bit len 16
|
||
|
uint16_t d270; // bit len 16
|
||
|
uint16_t d315; // bit len 16
|
||
|
uint8_t sensor_id; // bit len 8
|
||
|
uint8_t sensor_type; // bit len 5
|
||
|
uint8_t reading_type; // bit len 3
|
||
|
} uavcan_proximity_t;
|
||
|
|
||
|
extern
|
||
|
uint32_t zrzk_equipment_range_sensor_Proximity_encode(uavcan_proximity_t* source, void* msg_buf);
|
||
|
|
||
|
extern
|
||
|
int32_t zrzk_equipment_range_sensor_Proximity_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_proximity_t* dest, uint8_t** dyn_arr_buf);
|
||
|
|
||
|
extern
|
||
|
uint32_t zrzk_equipment_range_sensor_Proximity_encode_internal(uavcan_proximity_t* source, void* msg_buf, uint32_t offset, uint8_t root_item);
|
||
|
|
||
|
extern
|
||
|
int32_t zrzk_equipment_range_sensor_Proximity_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_proximity_t* dest, uint8_t** dyn_arr_buf, int32_t offset);
|
||
|
|
||
|
#ifdef __cplusplus
|
||
|
} // extern "C"
|
||
|
#endif
|
||
|
#endif // __ZRZK_EQUIPMENT_RANGE_SENSOR_PROXIMITY
|