AP_Volz_Protocol.cpp 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157
  1. /*
  2. * AP_VOLZ_PROTOCOL.cpp
  3. *
  4. * Created on: Oct 31, 2017
  5. * Author: guy
  6. */
  7. #include <AP_HAL/AP_HAL.h>
  8. #include <SRV_Channel/SRV_Channel.h>
  9. #include "AP_Volz_Protocol.h"
  10. extern const AP_HAL::HAL& hal;
  11. const AP_Param::GroupInfo AP_Volz_Protocol::var_info[] = {
  12. // @Param: MASK
  13. // @DisplayName: Channel Bitmask
  14. // @Description: Enable of volz servo protocol to specific channels
  15. // @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
  16. // @User: Standard
  17. AP_GROUPINFO("MASK", 1, AP_Volz_Protocol, bitmask, 0),
  18. AP_GROUPEND
  19. };
  20. // constructor
  21. AP_Volz_Protocol::AP_Volz_Protocol(void)
  22. {
  23. // set defaults from the parameter table
  24. AP_Param::setup_object_defaults(this, var_info);
  25. }
  26. void AP_Volz_Protocol::init(void)
  27. {
  28. AP_SerialManager &serial_manager = AP::serialmanager();
  29. port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Volz,0);
  30. update_volz_bitmask(bitmask);
  31. }
  32. void AP_Volz_Protocol::update()
  33. {
  34. if (!initialised) {
  35. initialised = true;
  36. init();
  37. }
  38. if (port == nullptr) {
  39. return;
  40. }
  41. if (last_used_bitmask != uint32_t(bitmask.get())) {
  42. update_volz_bitmask(bitmask);
  43. }
  44. uint32_t now = AP_HAL::micros();
  45. if (now - last_volz_update_time < volz_time_frame_micros ||
  46. port->txspace() < VOLZ_DATA_FRAME_SIZE) {
  47. return;
  48. }
  49. last_volz_update_time = now;
  50. uint8_t i;
  51. uint16_t value;
  52. // loop for all 16 channels
  53. for (i=0; i<NUM_SERVO_CHANNELS; i++) {
  54. // check if current channel is needed for Volz protocol
  55. if (last_used_bitmask & (1U<<i)) {
  56. SRV_Channel *c = SRV_Channels::srv_channel(i);
  57. if (c == nullptr) {
  58. continue;
  59. }
  60. // check if current channel PWM is within range
  61. if (c->get_output_pwm() < c->get_output_min()) {
  62. value = 0;
  63. } else {
  64. value = c->get_output_pwm() - c->get_output_min();
  65. }
  66. // scale the PWM value to Volz value
  67. value = value + VOLZ_EXTENDED_POSITION_MIN;
  68. value = value * VOLZ_SCALE_VALUE / (c->get_output_max() - c->get_output_min());
  69. // make sure value stays in range
  70. if (value > VOLZ_EXTENDED_POSITION_MAX) {
  71. value = VOLZ_EXTENDED_POSITION_MAX;
  72. }
  73. // prepare Volz protocol data.
  74. uint8_t data[VOLZ_DATA_FRAME_SIZE];
  75. data[0] = VOLZ_SET_EXTENDED_POSITION_CMD;
  76. data[1] = i + 1; // send actuator id as 1 based index so ch1 will have id 1, ch2 will have id 2 ....
  77. data[2] = HIGHBYTE(value);
  78. data[3] = LOWBYTE(value);
  79. send_command(data);
  80. }
  81. }
  82. }
  83. // calculate CRC for volz serial protocol and send the data.
  84. void AP_Volz_Protocol::send_command(uint8_t data[VOLZ_DATA_FRAME_SIZE])
  85. {
  86. uint8_t i,j;
  87. uint16_t crc = 0xFFFF;
  88. // calculate Volz CRC value according to protocol definition
  89. for(i=0; i<4; i++) {
  90. // take input data into message that will be transmitted.
  91. crc = ((data[i] << 8) ^ crc);
  92. for(j=0; j<8; j++) {
  93. if (crc & 0x8000) {
  94. crc = (crc << 1) ^ 0x8005;
  95. } else {
  96. crc = crc << 1;
  97. }
  98. }
  99. }
  100. // add CRC result to the message
  101. data[4] = HIGHBYTE(crc);
  102. data[5] = LOWBYTE(crc);
  103. port->write(data, VOLZ_DATA_FRAME_SIZE);
  104. }
  105. void AP_Volz_Protocol::update_volz_bitmask(uint32_t new_bitmask)
  106. {
  107. uint8_t count = 0;
  108. last_used_bitmask = new_bitmask;
  109. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  110. if (new_bitmask & (1U<<i)) {
  111. count++;
  112. }
  113. }
  114. // have a safety margin of 20% to allow for not having full uart
  115. // utilisation. We really don't want to start filling the uart
  116. // buffer or we'll end up with servo lag
  117. const float safety = 1.3;
  118. // each channel take about 425.347us to transmit so total time will be ~ number of channels * 450us
  119. // rounded to 450 to make sure we don't go over the baud rate.
  120. uint32_t channels_micros = count * 450 * safety;
  121. // limit the minimum to 2500 will result a max refresh frequency of 400hz.
  122. if (channels_micros < 2500) {
  123. channels_micros = 2500;
  124. }
  125. volz_time_frame_micros = channels_micros;
  126. }