2017-11-02 23:27:29 -03:00
|
|
|
/*
|
|
|
|
* AP_VOLZ_PROTOCOL.h
|
|
|
|
*
|
|
|
|
* Created on: Oct 31, 2017
|
|
|
|
* Author: guy tzoler
|
|
|
|
*
|
|
|
|
* Baud-Rate: 115.200 bits per second
|
|
|
|
* Number of Data bits: 8
|
|
|
|
* Number of Stop bits: 1
|
|
|
|
* Parity: None
|
|
|
|
* Half/Full Duplex: Half Duplex
|
|
|
|
*
|
|
|
|
* Volz Command and Response are all 6 bytes
|
|
|
|
*
|
|
|
|
* Command
|
|
|
|
* byte | Communication Type
|
|
|
|
* 1 Command Code
|
|
|
|
* 2 Actuator ID
|
|
|
|
* 3 Argument 1
|
|
|
|
* 4 Argument 2
|
|
|
|
* 5 CRC High-byte
|
|
|
|
* 6 CRC Low-Byte
|
|
|
|
*
|
|
|
|
* byte | Communication Type
|
|
|
|
* 1 Response Code
|
|
|
|
* 2 Actuator ID
|
|
|
|
* 3 Argument 1
|
|
|
|
* 4 Argument 2
|
|
|
|
* 5 CRC High-byte
|
|
|
|
* 6 CRC Low-Byte
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
2022-04-08 04:20:50 -03:00
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
|
|
|
|
|
|
|
#ifndef AP_VOLZ_ENABLED
|
2023-04-14 00:47:53 -03:00
|
|
|
#define AP_VOLZ_ENABLED BOARD_FLASH_SIZE > 1024
|
2022-04-08 04:20:50 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#if AP_VOLZ_ENABLED
|
|
|
|
|
2017-11-02 23:27:29 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
|
|
|
|
class AP_Volz_Protocol {
|
|
|
|
public:
|
2017-12-12 21:06:15 -04:00
|
|
|
AP_Volz_Protocol();
|
2017-11-02 23:27:29 -03:00
|
|
|
|
|
|
|
/* Do not allow copies */
|
2022-02-25 01:06:30 -04:00
|
|
|
CLASS_NO_COPY(AP_Volz_Protocol);
|
2017-11-02 23:27:29 -03:00
|
|
|
|
2017-12-12 21:06:15 -04:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2024-04-04 10:05:19 -03:00
|
|
|
|
2017-11-02 23:27:29 -03:00
|
|
|
void update();
|
|
|
|
|
|
|
|
private:
|
2024-04-04 10:05:19 -03:00
|
|
|
|
|
|
|
// Command frame
|
|
|
|
union CMD {
|
|
|
|
struct PACKED {
|
|
|
|
uint8_t ID; // CMD ID
|
|
|
|
uint8_t actuator_id; // actuator send to or receiving from
|
|
|
|
uint8_t arg1; // CMD dependant argument 1
|
|
|
|
uint8_t arg2; // CMD dependant argument 2
|
|
|
|
uint8_t crc1;
|
|
|
|
uint8_t crc2;
|
|
|
|
};
|
|
|
|
uint8_t data[6];
|
|
|
|
};
|
|
|
|
|
2017-11-02 23:27:29 -03:00
|
|
|
AP_HAL::UARTDriver *port;
|
2024-04-04 10:05:19 -03:00
|
|
|
|
2017-11-02 23:27:29 -03:00
|
|
|
void init(void);
|
2024-04-04 10:05:19 -03:00
|
|
|
void send_command(CMD &cmd);
|
2017-11-02 23:27:29 -03:00
|
|
|
void update_volz_bitmask(uint32_t new_bitmask);
|
|
|
|
|
|
|
|
uint32_t last_volz_update_time;
|
|
|
|
uint32_t volz_time_frame_micros;
|
|
|
|
uint32_t last_used_bitmask;
|
|
|
|
|
|
|
|
AP_Int32 bitmask;
|
2024-04-04 10:07:05 -03:00
|
|
|
AP_Int16 range;
|
2017-11-02 23:27:29 -03:00
|
|
|
bool initialised;
|
|
|
|
};
|
2022-04-08 04:20:50 -03:00
|
|
|
|
|
|
|
#endif // AP_VOLZ_PROTOCOL
|