APM:Libraries
SoloGimbal_Parameters.cpp
Go to the documentation of this file.
2 #include <AP_HAL/AP_HAL.h>
3 
4 #include <stdio.h>
5 
6 extern const AP_HAL::HAL& hal;
7 
8 const uint32_t SoloGimbal_Parameters::_retry_period = 3000;
10 
12 {
13  reset();
14 }
15 
16 
18 {
19  memset(_params,0,sizeof(_params));
20  _last_request_ms = 0;
22 }
23 
25 {
26  switch(param) {
28  return "GMB_OFF_ACC_X";
30  return "GMB_OFF_ACC_Y";
32  return "GMB_OFF_ACC_Z";
34  return "GMB_GN_ACC_X";
36  return "GMB_GN_ACC_Y";
38  return "GMB_GN_ACC_Z";
40  return "GMB_OFF_GYRO_X";
42  return "GMB_OFF_GYRO_Y";
44  return "GMB_OFF_GYRO_Z";
46  return "GMB_OFF_JNT_X";
48  return "GMB_OFF_JNT_Y";
50  return "GMB_OFF_JNT_Z";
52  return "GMB_K_RATE";
54  return "GMB_POS_HOLD";
56  return "GMB_MAX_TORQUE";
58  return "GMB_SND_TORQUE";
60  return "GMB_SYSID";
62  return "GMB_FLASH";
63  default:
64  return "";
65  };
66 }
67 
69 {
70  for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
73  }
74  }
75 }
76 
78 {
79  for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
81  return false;
82  }
83  }
84  return true;
85 }
86 
88 {
89  for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
91  return false;
92  }
93  }
94  return true;
95 }
96 
97 void SoloGimbal_Parameters::get_param(gmb_param_t param, float& value, float def_val) {
98  if (!_params[param].seen) {
99  value = def_val;
100  } else {
101  value = _params[param].value;
102  }
103 }
104 
106  if ((_params[param].state == GMB_PARAMSTATE_CONSISTENT && param != GMB_PARAM_GMB_FLASH && is_equal(_params[param].value,value)) || _params[param].state == GMB_PARAMSTATE_NONEXISTANT) {
107  return;
108  }
109 
111  _params[param].value = value;
112  mavlink_msg_param_set_send(_chan, 0, MAV_COMP_ID_GIMBAL, get_param_name(param), _params[param].value, MAV_PARAM_TYPE_REAL32);
113 
115 }
116 
118 {
119  uint32_t tnow_ms = AP_HAL::millis();
120 
121  // retry initial param retrieval
122  if(!received_all()){
123  if (tnow_ms-_last_request_ms > _retry_period) {
124  _last_request_ms = tnow_ms;
125  mavlink_msg_param_request_list_send(_chan, 0, MAV_COMP_ID_GIMBAL);
126 
127  for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
128  if (!_params[i].seen) {
129  _params[i].fetch_attempts++;
130  }
131  }
132  }
133  }
134 
135  // retry param_set
136  for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
138  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);
139  if (!_params[i].seen) {
140  _params[i].fetch_attempts++;
141  }
142  }
143  }
144 
145  // check for nonexistent parameters
146  for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
149  hal.console->printf("Gimbal parameter %s timed out\n", get_param_name((gmb_param_t)i));
150  }
151  }
152 
154  bool done = true;
155  for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
157  done = false;
158  break;
159  }
160  }
161 
162  if (done) {
165  }
166  }
167 }
168 
169 void SoloGimbal_Parameters::handle_param_value(mavlink_message_t *msg)
170 {
171  mavlink_param_value_t packet;
172  mavlink_msg_param_value_decode(msg, &packet);
173 
175  if (dataflash != nullptr) {
176  dataflash->Log_Write_Parameter(packet.param_id, packet.param_value);
177  }
178 
179  for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
180  if (!strcmp(packet.param_id, get_param_name((gmb_param_t)i))) {
181  _params[i].seen = true;
182  switch(_params[i].state) {
186  _params[i].value = packet.param_value;
188  break;
190  _params[i].value = packet.param_value;
191  break;
193  if (i == GMB_PARAM_GMB_FLASH) {
194  if (_flashing_step == GMB_PARAM_FLASHING_WAITING_FOR_ACK && (int)packet.param_value == 1) {
196  }
197  _params[i].value = 0;
199  } else if (is_equal(packet.param_value,_params[i].value)) {
201  }
202  break;
203  }
204  break;
205  }
206  }
207 }
208 
210 {
211  Vector3f ret;
215  return ret;
216 }
218 {
219  Vector3f ret;
223  return ret;
224 }
225 
227 {
231 }
232 
234 {
238 }
239 
241 {
242  Vector3f ret;
246  return ret;
247 }
248 
250 {
254 }
255 
257 {
258  Vector3f ret;
262  return ret;
263 }
265 {
266  float ret;
268  return ret;
269 }
270 
272 {
274 }
275 
277 {
279 }
AP_HAL::UARTDriver * console
Definition: HAL.h:110
struct SoloGimbal_Parameters::@136 _params[MAVLINK_GIMBAL_NUM_TRACKED_PARAMS]
static const uint8_t _max_fetch_attempts
void set_accel_gain(const Vector3f &gain)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void Log_Write_Parameter(const char *name, float value)
Definition: DataFlash.cpp:603
gmb_flashing_step_t _flashing_step
static const uint32_t _retry_period
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
#define f(i)
T y
Definition: vector3.h:67
void get_param(gmb_param_t param, float &value, float def_val=0.0f)
uint32_t millis()
Definition: system.cpp:157
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
void set_gyro_bias(const Vector3f &bias)
void handle_param_value(mavlink_message_t *msg)
void set_param(gmb_param_t param, float value)
void set_accel_bias(const Vector3f &bias)
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
static const char * get_param_name(gmb_param_t param)
T x
Definition: vector3.h:67