APM:Libraries
AP_Volz_Protocol.h
Go to the documentation of this file.
1 /*
2  * AP_VOLZ_PROTOCOL.h
3  *
4  * Created on: Oct 31, 2017
5  * Author: guy tzoler
6  *
7  * Baud-Rate: 115.200 bits per second
8  * Number of Data bits: 8
9  * Number of Stop bits: 1
10  * Parity: None
11  * Half/Full Duplex: Half Duplex
12  *
13  * Volz Command and Response are all 6 bytes
14  *
15  * Command
16  * byte | Communication Type
17  * 1 Command Code
18  * 2 Actuator ID
19  * 3 Argument 1
20  * 4 Argument 2
21  * 5 CRC High-byte
22  * 6 CRC Low-Byte
23  *
24  * byte | Communication Type
25  * 1 Response Code
26  * 2 Actuator ID
27  * 3 Argument 1
28  * 4 Argument 2
29  * 5 CRC High-byte
30  * 6 CRC Low-Byte
31  *
32  */
33 
34 #pragma once
35 
36 #include <AP_HAL/AP_HAL.h>
38 #include <AP_Param/AP_Param.h>
39 
40 //#include <GCS_MAVLink/GCS.h>
41 
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
46 
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
50 
52 public:
54 
55  /* Do not allow copies */
56  AP_Volz_Protocol(const AP_Volz_Protocol &other) = delete;
58 
59  static const struct AP_Param::GroupInfo var_info[];
60 
61  void update();
62 
63 private:
65 
66  void init(void);
67  void send_command(uint8_t data[VOLZ_DATA_FRAME_SIZE]);
68  void update_volz_bitmask(uint32_t new_bitmask);
69 
73 
74  AP_Int32 bitmask;
76 };
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