Describes an interface classes can implement to receive and handle mavlink messages. More...
#include <param_listener_interface.h>

Public Member Functions | |
| virtual void | on_new_param_received (std::string name, double value)=0 |
| Called when a parameter is received from the autopilot for the first time. More... | |
| virtual void | on_param_value_updated (std::string name, double value)=0 |
| Called when an updated value is received for a parameter. More... | |
| virtual void | on_params_saved_change (bool unsaved_changes)=0 |
| Called when the status of whether there are unsaved parameters changes. More... | |
Describes an interface classes can implement to receive and handle mavlink messages.
Definition at line 47 of file param_listener_interface.h.
|
pure virtual |
Called when a parameter is received from the autopilot for the first time.
| name | The name of the parameter |
| value | The value of the parameter |
Implemented in rosflight_io::rosflightIO.
|
pure virtual |
Called when an updated value is received for a parameter.
| name | The name of the parameter |
| value | The updated value of the parameter |
Implemented in rosflight_io::rosflightIO.
|
pure virtual |
Called when the status of whether there are unsaved parameters changes.
| unsaved_changes | True if there are parameters that have been set but not saved on the autopilot |
Implemented in rosflight_io::rosflightIO.