57 init(name, index, type, raw_value);
127 value_ = fromRawValue<int8_t>(raw_value);
130 value_ = fromRawValue<int16_t>(raw_value);
133 value_ = fromRawValue<int32_t>(raw_value);
136 value_ = fromRawValue<uint8_t>(raw_value);
139 value_ = fromRawValue<uint16_t>(raw_value);
142 value_ = fromRawValue<uint32_t>(raw_value);
145 value_ = fromRawValue<float>(raw_value);
162 raw_value = toRawValue<int8_t>(value);
165 raw_value = toRawValue<int16_t>(value);
168 raw_value = toRawValue<int32_t>(value);
171 raw_value = toRawValue<uint8_t>(value);
174 raw_value = toRawValue<uint16_t>(value);
177 raw_value = toRawValue<uint32_t>(value);
180 raw_value = toRawValue<float>(value);
194 cast_value = toCastValue<int8_t>(value);
197 cast_value = toCastValue<int16_t>(value);
200 cast_value = toCastValue<int32_t>(value);
203 cast_value = toCastValue<uint8_t>(value);
206 cast_value = toCastValue<uint16_t>(value);
209 cast_value = toCastValue<uint32_t>(value);
212 cast_value = toCastValue<float>(value);
void setFromRawValue(float raw_value)
#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN
float expected_raw_value_
void requestSet(double value, mavlink_message_t *msg)
std::string getName() const
MAV_PARAM_TYPE getType() const
bool handleUpdate(const mavlink_param_value_t &msg)
double getCastValue(double value)
static uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type)
Pack a param_set message.
void init(std::string name, int index, MAV_PARAM_TYPE type, float raw_value)