42 #define VOLZ_SCALE_VALUE (uint16_t)(VOLZ_EXTENDED_POSITION_MAX - VOLZ_EXTENDED_POSITION_MIN) // Extended Position Data Format defines 100 as 0x0F80, which results in 1920 steps for +100 deg and 1920 steps for -100 degs meaning if you take movement a scaled between -1 ... 1 and multiply by 1920 you get the travel from center 43 #define VOLZ_SET_EXTENDED_POSITION_CMD 0xDC 44 #define VOLZ_SET_EXTENDED_POSITION_RSP 0x2C 45 #define VOLZ_DATA_FRAME_SIZE 6 47 #define VOLZ_EXTENDED_POSITION_MIN 0x0080 // Extended Position Data Format defines -100 as 0x0080 decimal 128 48 #define VOLZ_EXTENDED_POSITION_CENTER 0x0800 // Extended Position Data Format defines 0 as 0x0800 - decimal 2048 49 #define VOLZ_EXTENDED_POSITION_MAX 0x0F80 // Extended Position Data Format defines +100 as 0x0F80 decimal 3968 -> full range decimal 3840 static const struct AP_Param::GroupInfo var_info[]
uint32_t last_used_bitmask
AP_HAL::UARTDriver * port
A system for managing and storing variables that are of general interest to the system.
AP_Volz_Protocol & operator=(const AP_Volz_Protocol &)=delete
uint32_t volz_time_frame_micros
#define VOLZ_DATA_FRAME_SIZE
void send_command(uint8_t data[VOLZ_DATA_FRAME_SIZE])
void update_volz_bitmask(uint32_t new_bitmask)
uint32_t last_volz_update_time