12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576 |
- #pragma once
- #include <AP_HAL/AP_HAL.h>
- #include <AP_SerialManager/AP_SerialManager.h>
- #include <AP_Param/AP_Param.h>
- #define VOLZ_SCALE_VALUE (uint16_t)(VOLZ_EXTENDED_POSITION_MAX - VOLZ_EXTENDED_POSITION_MIN)
- #define VOLZ_SET_EXTENDED_POSITION_CMD 0xDC
- #define VOLZ_SET_EXTENDED_POSITION_RSP 0x2C
- #define VOLZ_DATA_FRAME_SIZE 6
- #define VOLZ_EXTENDED_POSITION_MIN 0x0080
- #define VOLZ_EXTENDED_POSITION_CENTER 0x0800
- #define VOLZ_EXTENDED_POSITION_MAX 0x0F80
- class AP_Volz_Protocol {
- public:
- AP_Volz_Protocol();
-
- AP_Volz_Protocol(const AP_Volz_Protocol &other) = delete;
- AP_Volz_Protocol &operator=(const AP_Volz_Protocol&) = delete;
- static const struct AP_Param::GroupInfo var_info[];
-
- void update();
- private:
- AP_HAL::UARTDriver *port;
-
- void init(void);
- void send_command(uint8_t data[VOLZ_DATA_FRAME_SIZE]);
- 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;
- bool initialised;
- };
|