APM:Libraries
SoloGimbal_Parameters.h
Go to the documentation of this file.
1 #pragma once
2 #include <AP_Math/AP_Math.h>
3 #include <AP_Common/AP_Common.h>
5 #include <DataFlash/DataFlash.h>
6 
8  GMB_PARAMSTATE_NOT_YET_READ=0, // parameter has yet to be initialized
9  GMB_PARAMSTATE_FETCH_AGAIN=1, // parameter is being fetched
10  GMB_PARAMSTATE_ATTEMPTING_TO_SET=2, // parameter is being set
11  GMB_PARAMSTATE_CONSISTENT=3, // parameter is consistent
12  GMB_PARAMSTATE_NONEXISTANT=4 // parameter does not seem to exist
13 };
14 
35 };
36 
41 };
42 
44 {
45 public:
47  void reset();
48 
49  bool initialized();
50  bool received_all();
51  void fetch_params();
52 
53  void get_param(gmb_param_t param, float& value, float def_val = 0.0f);
54  void set_param(gmb_param_t param, float value);
55 
56  void update();
57  void handle_param_value(mavlink_message_t *msg);
58 
61  void set_accel_bias(const Vector3f& bias);
62  void set_accel_gain(const Vector3f& gain);
64  void set_gyro_bias(const Vector3f& bias);
66 
67  float get_K_rate();
68  void flash();
69  bool flashing();
70 
71  void set_channel(mavlink_channel_t chan) { _chan = chan; }
72 
73 private:
74  static const char* get_param_name(gmb_param_t param);
75 
76  static const uint32_t _retry_period;
77  static const uint8_t _max_fetch_attempts;
78 
79  struct {
80  float value;
82  uint8_t fetch_attempts;
83  bool seen;
85 
86  uint32_t _last_request_ms;
88 
89  mavlink_channel_t _chan;
90 };
struct SoloGimbal_Parameters::@136 _params[MAVLINK_GIMBAL_NUM_TRACKED_PARAMS]
static const uint8_t _max_fetch_attempts
void set_channel(mavlink_channel_t chan)
void set_accel_gain(const Vector3f &gain)
gmb_flashing_step_t
gmb_flashing_step_t _flashing_step
static const uint32_t _retry_period
gmb_param_state_t
#define f(i)
void get_param(gmb_param_t param, float &value, float def_val=0.0f)
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)
Common definitions and utility routines for the ArduPilot libraries.
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
static const char * get_param_name(gmb_param_t param)