SoloGimbal_Parameters.cpp 9.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294
  1. #include "SoloGimbal_Parameters.h"
  2. #include <AP_HAL/AP_HAL.h>
  3. #include <AP_Logger/AP_Logger.h>
  4. #include <GCS_MAVLink/GCS.h>
  5. #include <stdio.h>
  6. extern const AP_HAL::HAL& hal;
  7. const uint32_t SoloGimbal_Parameters::_retry_period = 3000;
  8. const uint8_t SoloGimbal_Parameters::_max_fetch_attempts = 5;
  9. SoloGimbal_Parameters::SoloGimbal_Parameters()
  10. {
  11. reset();
  12. }
  13. void SoloGimbal_Parameters::reset()
  14. {
  15. memset(_params,0,sizeof(_params));
  16. _last_request_ms = 0;
  17. _last_set_ms = 0;
  18. _flashing_step = GMB_PARAM_NOT_FLASHING;
  19. }
  20. const char* SoloGimbal_Parameters::get_param_name(gmb_param_t param)
  21. {
  22. switch(param) {
  23. case GMB_PARAM_GMB_OFF_ACC_X:
  24. return "GMB_OFF_ACC_X";
  25. case GMB_PARAM_GMB_OFF_ACC_Y:
  26. return "GMB_OFF_ACC_Y";
  27. case GMB_PARAM_GMB_OFF_ACC_Z:
  28. return "GMB_OFF_ACC_Z";
  29. case GMB_PARAM_GMB_GN_ACC_X:
  30. return "GMB_GN_ACC_X";
  31. case GMB_PARAM_GMB_GN_ACC_Y:
  32. return "GMB_GN_ACC_Y";
  33. case GMB_PARAM_GMB_GN_ACC_Z:
  34. return "GMB_GN_ACC_Z";
  35. case GMB_PARAM_GMB_OFF_GYRO_X:
  36. return "GMB_OFF_GYRO_X";
  37. case GMB_PARAM_GMB_OFF_GYRO_Y:
  38. return "GMB_OFF_GYRO_Y";
  39. case GMB_PARAM_GMB_OFF_GYRO_Z:
  40. return "GMB_OFF_GYRO_Z";
  41. case GMB_PARAM_GMB_OFF_JNT_X:
  42. return "GMB_OFF_JNT_X";
  43. case GMB_PARAM_GMB_OFF_JNT_Y:
  44. return "GMB_OFF_JNT_Y";
  45. case GMB_PARAM_GMB_OFF_JNT_Z:
  46. return "GMB_OFF_JNT_Z";
  47. case GMB_PARAM_GMB_K_RATE:
  48. return "GMB_K_RATE";
  49. case GMB_PARAM_GMB_POS_HOLD:
  50. return "GMB_POS_HOLD";
  51. case GMB_PARAM_GMB_MAX_TORQUE:
  52. return "GMB_MAX_TORQUE";
  53. case GMB_PARAM_GMB_SND_TORQUE:
  54. return "GMB_SND_TORQUE";
  55. case GMB_PARAM_GMB_SYSID:
  56. return "GMB_SYSID";
  57. case GMB_PARAM_GMB_FLASH:
  58. return "GMB_FLASH";
  59. default:
  60. return "";
  61. };
  62. }
  63. void SoloGimbal_Parameters::fetch_params()
  64. {
  65. for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
  66. if (_params[i].state != GMB_PARAMSTATE_NOT_YET_READ) {
  67. _params[i].state = GMB_PARAMSTATE_FETCH_AGAIN;
  68. }
  69. }
  70. }
  71. bool SoloGimbal_Parameters::initialized()
  72. {
  73. for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
  74. if(_params[i].state == GMB_PARAMSTATE_NOT_YET_READ) {
  75. return false;
  76. }
  77. }
  78. return true;
  79. }
  80. bool SoloGimbal_Parameters::received_all()
  81. {
  82. for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
  83. if(_params[i].state == GMB_PARAMSTATE_NOT_YET_READ || _params[i].state == GMB_PARAMSTATE_FETCH_AGAIN) {
  84. return false;
  85. }
  86. }
  87. return true;
  88. }
  89. void SoloGimbal_Parameters::get_param(gmb_param_t param, float& value, float def_val) {
  90. if (!_params[param].seen) {
  91. value = def_val;
  92. } else {
  93. value = _params[param].value;
  94. }
  95. }
  96. void SoloGimbal_Parameters::set_param(gmb_param_t param, float value) {
  97. if ((_params[param].state == GMB_PARAMSTATE_CONSISTENT && param != GMB_PARAM_GMB_FLASH &&
  98. is_equal(_params[param].value,value)) || _params[param].state == GMB_PARAMSTATE_NONEXISTANT ||
  99. !HAVE_PAYLOAD_SPACE(_chan, PARAM_SET)) {
  100. return;
  101. }
  102. _params[param].state = GMB_PARAMSTATE_ATTEMPTING_TO_SET;
  103. _params[param].value = value;
  104. // make a temporary copy of the ID; mavlink_msg_param_set_send
  105. // expects an array of the full length
  106. char tmp_name[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN+1] {};
  107. strncpy(tmp_name, get_param_name(param), MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
  108. mavlink_msg_param_set_send(_chan, 0, MAV_COMP_ID_GIMBAL, tmp_name, _params[param].value, MAV_PARAM_TYPE_REAL32);
  109. _last_set_ms = AP_HAL::millis();
  110. }
  111. void SoloGimbal_Parameters::update()
  112. {
  113. uint32_t tnow_ms = AP_HAL::millis();
  114. // retry initial param retrieval
  115. if(!received_all() && ((tnow_ms - _last_request_ms) > _retry_period) &&
  116. (HAVE_PAYLOAD_SPACE(_chan, PARAM_REQUEST_LIST))) {
  117. _last_request_ms = tnow_ms;
  118. mavlink_msg_param_request_list_send(_chan, 0, MAV_COMP_ID_GIMBAL);
  119. for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
  120. if (!_params[i].seen) {
  121. _params[i].fetch_attempts++;
  122. }
  123. }
  124. }
  125. // retry param_set
  126. for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
  127. if (!HAVE_PAYLOAD_SPACE(_chan, PARAM_SET)) {
  128. break;
  129. }
  130. if ((_params[i].state == GMB_PARAMSTATE_ATTEMPTING_TO_SET) && (tnow_ms - _last_set_ms > _retry_period)) {
  131. mavlink_msg_param_set_send(_chan, 0, MAV_COMP_ID_GIMBAL, get_param_name((gmb_param_t)i), _params[i].value, MAV_PARAM_TYPE_REAL32);
  132. _last_set_ms = AP_HAL::millis();
  133. if (!_params[i].seen) {
  134. _params[i].fetch_attempts++;
  135. }
  136. }
  137. }
  138. // check for nonexistent parameters
  139. for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
  140. if (!_params[i].seen && _params[i].fetch_attempts > _max_fetch_attempts) {
  141. _params[i].state = GMB_PARAMSTATE_NONEXISTANT;
  142. hal.console->printf("Gimbal parameter %s timed out\n", get_param_name((gmb_param_t)i));
  143. }
  144. }
  145. if(_flashing_step == GMB_PARAM_FLASHING_WAITING_FOR_SET) {
  146. bool done = true;
  147. for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
  148. if (_params[i].state == GMB_PARAMSTATE_ATTEMPTING_TO_SET) {
  149. done = false;
  150. break;
  151. }
  152. }
  153. if (done) {
  154. _flashing_step = GMB_PARAM_FLASHING_WAITING_FOR_ACK;
  155. set_param(GMB_PARAM_GMB_FLASH,69.0f);
  156. }
  157. }
  158. }
  159. void SoloGimbal_Parameters::handle_param_value(const mavlink_message_t &msg)
  160. {
  161. mavlink_param_value_t packet;
  162. mavlink_msg_param_value_decode(&msg, &packet);
  163. AP_Logger *logger = AP_Logger::get_singleton();
  164. if (logger != nullptr) {
  165. logger->Write_Parameter(packet.param_id, packet.param_value);
  166. }
  167. for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
  168. if (!strcmp(packet.param_id, get_param_name((gmb_param_t)i))) {
  169. _params[i].seen = true;
  170. switch(_params[i].state) {
  171. case GMB_PARAMSTATE_NONEXISTANT:
  172. case GMB_PARAMSTATE_NOT_YET_READ:
  173. case GMB_PARAMSTATE_FETCH_AGAIN:
  174. _params[i].value = packet.param_value;
  175. _params[i].state = GMB_PARAMSTATE_CONSISTENT;
  176. break;
  177. case GMB_PARAMSTATE_CONSISTENT:
  178. _params[i].value = packet.param_value;
  179. break;
  180. case GMB_PARAMSTATE_ATTEMPTING_TO_SET:
  181. if (i == GMB_PARAM_GMB_FLASH) {
  182. if (_flashing_step == GMB_PARAM_FLASHING_WAITING_FOR_ACK && (int)packet.param_value == 1) {
  183. _flashing_step = GMB_PARAM_NOT_FLASHING;
  184. }
  185. _params[i].value = 0;
  186. _params[i].state = GMB_PARAMSTATE_CONSISTENT;
  187. } else if (is_equal(packet.param_value,_params[i].value)) {
  188. _params[i].state = GMB_PARAMSTATE_CONSISTENT;
  189. }
  190. break;
  191. }
  192. break;
  193. }
  194. }
  195. }
  196. Vector3f SoloGimbal_Parameters::get_accel_bias()
  197. {
  198. Vector3f ret;
  199. get_param(GMB_PARAM_GMB_OFF_ACC_X,ret.x);
  200. get_param(GMB_PARAM_GMB_OFF_ACC_Y,ret.y);
  201. get_param(GMB_PARAM_GMB_OFF_ACC_Z,ret.z);
  202. return ret;
  203. }
  204. Vector3f SoloGimbal_Parameters::get_accel_gain()
  205. {
  206. Vector3f ret;
  207. get_param(GMB_PARAM_GMB_GN_ACC_X,ret.x,1.0f);
  208. get_param(GMB_PARAM_GMB_GN_ACC_Y,ret.y,1.0f);
  209. get_param(GMB_PARAM_GMB_GN_ACC_Z,ret.z,1.0f);
  210. return ret;
  211. }
  212. void SoloGimbal_Parameters::set_accel_bias(const Vector3f& bias)
  213. {
  214. set_param(GMB_PARAM_GMB_OFF_ACC_X, bias.x);
  215. set_param(GMB_PARAM_GMB_OFF_ACC_Y, bias.y);
  216. set_param(GMB_PARAM_GMB_OFF_ACC_Z, bias.z);
  217. }
  218. void SoloGimbal_Parameters::set_accel_gain(const Vector3f& gain)
  219. {
  220. set_param(GMB_PARAM_GMB_GN_ACC_X, gain.x);
  221. set_param(GMB_PARAM_GMB_GN_ACC_Y, gain.y);
  222. set_param(GMB_PARAM_GMB_GN_ACC_Z, gain.z);
  223. }
  224. Vector3f SoloGimbal_Parameters::get_gyro_bias()
  225. {
  226. Vector3f ret;
  227. get_param(GMB_PARAM_GMB_OFF_GYRO_X,ret.x);
  228. get_param(GMB_PARAM_GMB_OFF_GYRO_Y,ret.y);
  229. get_param(GMB_PARAM_GMB_OFF_GYRO_Z,ret.z);
  230. return ret;
  231. }
  232. void SoloGimbal_Parameters::set_gyro_bias(const Vector3f& bias)
  233. {
  234. set_param(GMB_PARAM_GMB_OFF_GYRO_X,bias.x);
  235. set_param(GMB_PARAM_GMB_OFF_GYRO_Y,bias.y);
  236. set_param(GMB_PARAM_GMB_OFF_GYRO_Z,bias.z);
  237. }
  238. Vector3f SoloGimbal_Parameters::get_joint_bias()
  239. {
  240. Vector3f ret;
  241. get_param(GMB_PARAM_GMB_OFF_JNT_X,ret.x);
  242. get_param(GMB_PARAM_GMB_OFF_JNT_Y,ret.y);
  243. get_param(GMB_PARAM_GMB_OFF_JNT_Z,ret.z);
  244. return ret;
  245. }
  246. float SoloGimbal_Parameters::get_K_rate()
  247. {
  248. float ret;
  249. get_param(GMB_PARAM_GMB_K_RATE,ret);
  250. return ret;
  251. }
  252. void SoloGimbal_Parameters::flash()
  253. {
  254. _flashing_step = GMB_PARAM_FLASHING_WAITING_FOR_SET;
  255. }
  256. bool SoloGimbal_Parameters::flashing()
  257. {
  258. return _flashing_step != GMB_PARAM_NOT_FLASHING;
  259. }