Public Types | |
using | MT = mavlink::common::MAV_PARAM_TYPE |
using | PARAM_SET = mavlink::common::msg::PARAM_SET |
using | XmlRpcValue = XmlRpc::XmlRpcValue |
Public Member Functions | |
void | set_value (mavlink::common::msg::PARAM_VALUE &pmsg) |
void | set_value_apm_quirk (mavlink::common::msg::PARAM_VALUE &pmsg) |
int64_t | to_integer () |
mavros_msgs::Param | to_msg () |
PARAM_SET | to_param_set () |
Make PARAM_SET message. Set target ids manually! More... | |
PARAM_SET | to_param_set_apm_qurk () |
Make PARAM_SET message. Set target ids manually! More... | |
double | to_real () |
std::string | to_string () const |
Static Public Member Functions | |
static bool | check_exclude_param_id (std::string param_id) |
Public Attributes | |
uint16_t | param_count |
std::string | param_id |
uint16_t | param_index |
XmlRpcValue | param_value |
Parameter storage.
Stores parameter value.
APM uses:
PX4:
So no reason to really use boost::any. But feel free to fire an issue if your AP do not like it.