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";
54 return "GMB_POS_HOLD";
56 return "GMB_MAX_TORQUE";
58 return "GMB_SND_TORQUE";
125 mavlink_msg_param_request_list_send(
_chan, 0, MAV_COMP_ID_GIMBAL);
171 mavlink_param_value_t packet;
172 mavlink_msg_param_value_decode(msg, &packet);
175 if (dataflash !=
nullptr) {
186 _params[i].value = packet.param_value;
190 _params[i].value = packet.param_value;
AP_HAL::UARTDriver * console
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 -*-
void Log_Write_Parameter(const char *name, float value)
gmb_flashing_step_t _flashing_step
Vector3f get_accel_gain()
uint32_t _last_request_ms
static const uint32_t _retry_period
Vector3f get_joint_bias()
virtual void printf(const char *,...) FMT_PRINTF(2
void get_param(gmb_param_t param, float &value, float def_val=0.0f)
static DataFlash_Class * instance(void)
void set_gyro_bias(const Vector3f &bias)
void handle_param_value(mavlink_message_t *msg)
void set_param(gmb_param_t param, float value)
Vector3f get_accel_bias()
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)
static const char * get_param_name(gmb_param_t param)