static void _encode_uavcan_protocol_GetDataTypeInfo_req(uint8_t[] buffer, uavcan_protocol_GetDataTypeInfo_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { memset(buffer, 0, 8); canardEncodeScalar(buffer, 0, 16, msg.id); chunk_cb(buffer, 16, ctx); _encode_uavcan_protocol_DataTypeKind(buffer, msg.kind, chunk_cb, ctx, false); if (!tao) { memset(buffer, 0, 8); canardEncodeScalar(buffer, 0, 7, msg.name_len); chunk_cb(buffer, 7, ctx); } for (int i = 0; i < msg.name_len; i++) { memset(buffer, 0, 8); canardEncodeScalar(buffer, 0, 8, msg.name[i]); chunk_cb(buffer, 8, ctx); } }
public static uavcan_protocol_GetDataTypeInfo_req ByteArrayToDroneCANMsg(byte[] transfer, int startoffset) { var ans = new uavcan_protocol_GetDataTypeInfo_req(); ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray())); return(ans); }
static void _decode_uavcan_protocol_GetDataTypeInfo_req(CanardRxTransfer transfer, ref uint32_t bit_ofs, uavcan_protocol_GetDataTypeInfo_req msg, bool tao) { canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.id); bit_ofs += 16; _decode_uavcan_protocol_DataTypeKind(transfer, ref bit_ofs, msg.kind, false); if (!tao) { canardDecodeScalar(transfer, bit_ofs, 7, false, ref msg.name_len); bit_ofs += 7; } else { msg.name_len = (uint8_t)(((transfer.payload_len * 8) - bit_ofs) / 8); } msg.name = new uint8_t[msg.name_len]; for (int i = 0; i < msg.name_len; i++) { canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.name[i]); bit_ofs += 8; } }
static uint32_t decode_uavcan_protocol_GetDataTypeInfo_req(CanardRxTransfer transfer, uavcan_protocol_GetDataTypeInfo_req msg) { uint32_t bit_ofs = 0; _decode_uavcan_protocol_GetDataTypeInfo_req(transfer, ref bit_ofs, msg, true); return((bit_ofs + 7) / 8); }
static void encode_uavcan_protocol_GetDataTypeInfo_req(uavcan_protocol_GetDataTypeInfo_req msg, uavcan_serializer_chunk_cb_ptr_t chunk_cb, object ctx) { uint8_t[] buffer = new uint8_t[8]; _encode_uavcan_protocol_GetDataTypeInfo_req(buffer, msg, chunk_cb, ctx, true); }