mavsdk::ParamServer Class Reference ​
#include: param_server.h
Provide raw access to retrieve and provide server parameters.
Data Structures ​
struct AllParams
struct CustomParam
struct FloatParam
struct IntParam
Public Types ​
| Type | Description |
|---|---|
| enum Result | Possible results returned for param requests. |
| std::function< void(Result)> ResultCallback | Callback type for asynchronous ParamServer calls. |
| std::function< void(IntParam)> ChangedParamIntCallback | Callback type for subscribe_changed_param_int. |
| Handle< IntParam > ChangedParamIntHandle | Handle type for subscribe_changed_param_int. |
| std::function< void(FloatParam)> ChangedParamFloatCallback | Callback type for subscribe_changed_param_float. |
| Handle< FloatParam > ChangedParamFloatHandle | Handle type for subscribe_changed_param_float. |
| std::function< void(CustomParam)> ChangedParamCustomCallback | Callback type for subscribe_changed_param_custom. |
| Handle< CustomParam > ChangedParamCustomHandle | Handle type for subscribe_changed_param_custom. |
Public Member Functions ​
| Type | Name | Description |
|---|---|---|
| Â | ParamServer (std::shared_ptr< ServerComponent > server_component) | Constructor. Creates the plugin for a ServerComponent instance. |
| Â | ~ParamServer () override | Destructor (internal use only). |
| Â | ParamServer (const ParamServer & other) | Copy constructor. |
| Result | set_protocol (bool extended_protocol)const | Set param protocol. |
| std::pair< Result, int32_t > | retrieve_param_int (std::string name)const | Retrieve an int parameter. |
| Result | provide_param_int (std::string name, int32_t value)const | Provide an int parameter. |
| std::pair< Result, float > | retrieve_param_float (std::string name)const | Retrieve a float parameter. |
| Result | provide_param_float (std::string name, float value)const | Provide a float parameter. |
| std::pair< Result, std::string > | retrieve_param_custom (std::string name)const | Retrieve a custom parameter. |
| Result | provide_param_custom (std::string name, std::string value)const | Provide a custom parameter. |
| ParamServer::AllParams | retrieve_all_params () const | Retrieve all parameters. |
| ChangedParamIntHandle | subscribe_changed_param_int (const ChangedParamIntCallback & callback) | Subscribe to changed int param. |
| void | unsubscribe_changed_param_int (ChangedParamIntHandle handle) | Unsubscribe from subscribe_changed_param_int. |
| ChangedParamFloatHandle | subscribe_changed_param_float (const ChangedParamFloatCallback & callback) | Subscribe to changed float param. |
| void | unsubscribe_changed_param_float (ChangedParamFloatHandle handle) | Unsubscribe from subscribe_changed_param_float. |
| ChangedParamCustomHandle | subscribe_changed_param_custom (const ChangedParamCustomCallback & callback) | Subscribe to changed custom param. |
| void | unsubscribe_changed_param_custom (ChangedParamCustomHandle handle) | Unsubscribe from subscribe_changed_param_custom. |
| const ParamServer & | operator= (const ParamServer &)=delete | Equality operator (object is not copyable). |
Constructor & Destructor Documentation ​
ParamServer() ​
mavsdk::ParamServer::ParamServer(std::shared_ptr< ServerComponent > server_component)Constructor. Creates the plugin for a ServerComponent instance.
The plugin is typically created as shown below:
auto param_server = ParamServer(server_component);Parameters
- std::shared_ptr< ServerComponent > server_component - The ServerComponent instance associated with this server plugin.
~ParamServer() ​
mavsdk::ParamServer::~ParamServer() overrideDestructor (internal use only).
ParamServer() ​
mavsdk::ParamServer::ParamServer(const ParamServer &other)Copy constructor.
Parameters
- const ParamServer& other -
Member Typdef Documentation ​
typedef ResultCallback ​
using mavsdk::ParamServer::ResultCallback = std::function<void(Result)>Callback type for asynchronous ParamServer calls.
typedef ChangedParamIntCallback ​
using mavsdk::ParamServer::ChangedParamIntCallback = std::function<void(IntParam)>Callback type for subscribe_changed_param_int.
typedef ChangedParamIntHandle ​
using mavsdk::ParamServer::ChangedParamIntHandle = Handle<IntParam>Handle type for subscribe_changed_param_int.
typedef ChangedParamFloatCallback ​
using mavsdk::ParamServer::ChangedParamFloatCallback = std::function<void(FloatParam)>Callback type for subscribe_changed_param_float.
typedef ChangedParamFloatHandle ​
using mavsdk::ParamServer::ChangedParamFloatHandle = Handle<FloatParam>Handle type for subscribe_changed_param_float.
typedef ChangedParamCustomCallback ​
using mavsdk::ParamServer::ChangedParamCustomCallback = std::function<void(CustomParam)>Callback type for subscribe_changed_param_custom.
typedef ChangedParamCustomHandle ​
using mavsdk::ParamServer::ChangedParamCustomHandle = Handle<CustomParam>Handle type for subscribe_changed_param_custom.
Member Enumeration Documentation ​
enum Result ​
Possible results returned for param requests.
| Value | Description |
|---|---|
Unknown | Unknown result. |
Success | Request succeeded. |
NotFound | Not Found. |
WrongType | Wrong type. |
ParamNameTooLong | Parameter name too long (> 16). |
NoSystem | No system available. |
ParamValueTooLong | Parameter name too long (> 128). |
Member Function Documentation ​
set_protocol() ​
Result mavsdk::ParamServer::set_protocol(bool extended_protocol) constSet param protocol.
The extended param protocol is used by default. This allows to use the previous/normal one.
Note that camera definition files are meant to implement/use the extended protocol.
This function is blocking.
Parameters
- bool extended_protocol -
Returns
 Result - Result of request.
retrieve_param_int() ​
std::pair< Result, int32_t > mavsdk::ParamServer::retrieve_param_int(std::string name) constRetrieve an int parameter.
If the type is wrong, the result will be WRONG_TYPE.
This function is blocking.
Parameters
- std::string name -
Returns
 std::pair< Result, int32_t > - Result of request.
provide_param_int() ​
Result mavsdk::ParamServer::provide_param_int(std::string name, int32_t value) constProvide an int parameter.
If the type is wrong, the result will be WRONG_TYPE.
This function is blocking.
Parameters
- std::string name -
- int32_t value -
Returns
 Result - Result of request.
retrieve_param_float() ​
std::pair< Result, float > mavsdk::ParamServer::retrieve_param_float(std::string name) constRetrieve a float parameter.
If the type is wrong, the result will be WRONG_TYPE.
This function is blocking.
Parameters
- std::string name -
Returns
 std::pair< Result, float > - Result of request.
provide_param_float() ​
Result mavsdk::ParamServer::provide_param_float(std::string name, float value) constProvide a float parameter.
If the type is wrong, the result will be WRONG_TYPE.
This function is blocking.
Parameters
- std::string name -
- float value -
Returns
 Result - Result of request.
retrieve_param_custom() ​
std::pair< Result, std::string > mavsdk::ParamServer::retrieve_param_custom(std::string name) constRetrieve a custom parameter.
If the type is wrong, the result will be WRONG_TYPE.
This function is blocking.
Parameters
- std::string name -
Returns
 std::pair< Result, std::string > - Result of request.
provide_param_custom() ​
Result mavsdk::ParamServer::provide_param_custom(std::string name, std::string value) constProvide a custom parameter.
If the type is wrong, the result will be WRONG_TYPE.
This function is blocking.
Parameters
- std::string name -
- std::string value -
Returns
 Result - Result of request.
retrieve_all_params() ​
ParamServer::AllParams mavsdk::ParamServer::retrieve_all_params() constRetrieve all parameters.
This function is blocking.
Returns
 ParamServer::AllParams - Result of request.
subscribe_changed_param_int() ​
ChangedParamIntHandle mavsdk::ParamServer::subscribe_changed_param_int(const ChangedParamIntCallback &callback)Subscribe to changed int param.
Parameters
- const ChangedParamIntCallback& callback -
Returns
unsubscribe_changed_param_int() ​
void mavsdk::ParamServer::unsubscribe_changed_param_int(ChangedParamIntHandle handle)Unsubscribe from subscribe_changed_param_int.
Parameters
- ChangedParamIntHandle handle -
subscribe_changed_param_float() ​
ChangedParamFloatHandle mavsdk::ParamServer::subscribe_changed_param_float(const ChangedParamFloatCallback &callback)Subscribe to changed float param.
Parameters
- const ChangedParamFloatCallback& callback -
Returns
unsubscribe_changed_param_float() ​
void mavsdk::ParamServer::unsubscribe_changed_param_float(ChangedParamFloatHandle handle)Unsubscribe from subscribe_changed_param_float.
Parameters
- ChangedParamFloatHandle handle -
subscribe_changed_param_custom() ​
ChangedParamCustomHandle mavsdk::ParamServer::subscribe_changed_param_custom(const ChangedParamCustomCallback &callback)Subscribe to changed custom param.
Parameters
- const ChangedParamCustomCallback& callback -
Returns
unsubscribe_changed_param_custom() ​
void mavsdk::ParamServer::unsubscribe_changed_param_custom(ChangedParamCustomHandle handle)Unsubscribe from subscribe_changed_param_custom.
Parameters
- ChangedParamCustomHandle handle -
operator=() ​
const ParamServer & mavsdk::ParamServer::operator=(const ParamServer &)=deleteEquality operator (object is not copyable).
Parameters
- const ParamServer& -
Returns
 const ParamServer & -

