APM:Libraries
AP_Volz_Protocol.cpp
Go to the documentation of this file.
1 /*
2  * AP_VOLZ_PROTOCOL.cpp
3  *
4  * Created on: Oct 31, 2017
5  * Author: guy
6  */
7 #include <AP_HAL/AP_HAL.h>
9 
10 #include "AP_Volz_Protocol.h"
11 
12 extern const AP_HAL::HAL& hal;
13 
15  // @Param: MASK
16  // @DisplayName: Channel Bitmask
17  // @Description: Enable of volz servo protocol to specific channels
18  // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
19  // @User: Standard
20  AP_GROUPINFO("MASK", 1, AP_Volz_Protocol, bitmask, 0),
21 
23 };
24 
25 // constructor
27 {
28  // set defaults from the parameter table
30 }
31 
33 {
37 }
38 
40 {
41  if (!initialised) {
42  initialised = true;
43  init();
44  }
45 
46  if (port == nullptr) {
47  return;
48  }
49 
50  if (last_used_bitmask != uint32_t(bitmask.get())) {
52  }
53 
54  uint32_t now = AP_HAL::micros();
57  return;
58  }
59 
61 
62  uint8_t i;
63  uint16_t value;
64 
65  // loop for all 16 channels
66  for (i=0; i<NUM_SERVO_CHANNELS; i++) {
67  // check if current channel is needed for Volz protocol
68  if (last_used_bitmask & (1U<<i)) {
69 
71  if (ch == nullptr) {
72  continue;
73  }
74 
75  // check if current channel PWM is within range
76  if (ch->get_output_pwm() < ch->get_output_min()) {
77  value = 0;
78  } else {
79  value = ch->get_output_pwm() - ch->get_output_min();
80  }
81 
82  // scale the PWM value to Volz value
83  value = value + VOLZ_EXTENDED_POSITION_MIN;
84  value = value * VOLZ_SCALE_VALUE / (ch->get_output_max() - ch->get_output_min());
85 
86  // make sure value stays in range
87  if (value > VOLZ_EXTENDED_POSITION_MAX) {
89  }
90 
91  // prepare Volz protocol data.
92  uint8_t data[VOLZ_DATA_FRAME_SIZE];
93 
95  data[1] = i + 1; // send actuator id as 1 based index so ch1 will have id 1, ch2 will have id 2 ....
96  data[2] = HIGHBYTE(value);
97  data[3] = LOWBYTE(value);
98 
99  send_command(data);
100  }
101  }
102 }
103 
104 // calculate CRC for volz serial protocol and send the data.
106 {
107  uint8_t i,j;
108  uint16_t crc = 0xFFFF;
109 
110  // calculate Volz CRC value according to protocol definition
111  for(i=0; i<4; i++) {
112  // take input data into message that will be transmitted.
113  crc = ((data[i] << 8) ^ crc);
114 
115  for(j=0; j<8; j++) {
116 
117  if (crc & 0x8000) {
118  crc = (crc << 1) ^ 0x8005;
119  } else {
120  crc = crc << 1;
121  }
122  }
123  }
124 
125  // add CRC result to the message
126  data[4] = HIGHBYTE(crc);
127  data[5] = LOWBYTE(crc);
128  port->write(data, VOLZ_DATA_FRAME_SIZE);
129 }
130 
131 void AP_Volz_Protocol::update_volz_bitmask(uint32_t new_bitmask)
132 {
133  uint8_t count = 0;
134  last_used_bitmask = new_bitmask;
135 
136  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
137  if (new_bitmask & (1U<<i)) {
138  count++;
139  }
140  }
141 
142  // have a safety margin of 20% to allow for not having full uart
143  // utilisation. We really don't want to start filling the uart
144  // buffer or we'll end up with servo lag
145  const float safety = 1.3;
146 
147  // each channel take about 425.347us to transmit so total time will be ~ number of channels * 450us
148  // rounded to 450 to make sure we don't go over the baud rate.
149  uint32_t channels_micros = count * 450 * safety;
150 
151  // limit the minimum to 2500 will result a max refresh frequency of 400hz.
152  if (channels_micros < 2500) {
153  channels_micros = 2500;
154  }
155 
156  volz_time_frame_micros = channels_micros;
157 }
static const struct AP_Param::GroupInfo var_info[]
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
uint32_t last_used_bitmask
AP_HAL::UARTDriver * port
uint16_t get_output_max(void) const
Definition: SRV_Channel.h:164
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
#define HIGHBYTE(i)
Definition: AP_Common.h:72
virtual uint32_t txspace()=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define VOLZ_EXTENDED_POSITION_MAX
#define VOLZ_SET_EXTENDED_POSITION_CMD
static SRV_Channel * srv_channel(uint8_t i)
Definition: SRV_Channel.h:405
AP_SerialManager & serialmanager()
virtual size_t write(uint8_t)=0
uint16_t get_output_min(void) const
Definition: SRV_Channel.h:161
#define LOWBYTE(i)
Definition: AP_Common.h:71
#define VOLZ_EXTENDED_POSITION_MIN
uint16_t get_output_pwm(void) const
Definition: SRV_Channel.h:139
uint32_t volz_time_frame_micros
#define VOLZ_DATA_FRAME_SIZE
float value
#define VOLZ_SCALE_VALUE
#define NUM_SERVO_CHANNELS
Definition: SRV_Channel.h:24
uint32_t micros()
Definition: system.cpp:152
#define AP_GROUPEND
Definition: AP_Param.h:121
void send_command(uint8_t data[VOLZ_DATA_FRAME_SIZE])
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
void update_volz_bitmask(uint32_t new_bitmask)
uint32_t last_volz_update_time
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214