MAV'RIC
|
Onboard parameters base class. More...
#include <onboard_parameters.hpp>
Classes | |
struct | conf_t |
Configuration for the module onboard parameters. More... | |
struct | param_entry_t |
Structure of onboard parameter. More... | |
Public Member Functions | |
Onboard_parameters (File &file, const State &state, Mavlink_message_handler &message_handler, const Mavlink_stream &mavlink_stream, const conf_t &config) | |
Constructor: Initialisation of the Parameter_Set structure by setting the number of onboard parameter to 0. | |
bool | add (uint32_t *val, const char *param_name) |
Register parameter in the internal parameter list that gets published to MAVlink. | |
bool | add (int32_t *val, const char *param_name) |
Register parameter in the internal parameter list that gets published to MAVlink. | |
bool | add (float *val, const char *param_name) |
Registers parameter in the internal parameter list that gets published to MAVlink. | |
bool | read_from_storage () |
Read onboard parameters from the file storage. | |
bool | write_to_storage () |
Write onboard parameters to the file storage. | |
bool | send_first_scheduled_parameter (void) |
Searches through the list of parameters, and send only the first scheduled parameter. | |
Static Public Member Functions | |
static conf_t | default_config (void) |
Default configuration. | |
Protected Member Functions | |
virtual uint32_t | max_count (void)=0 |
Get maximum number of parameters. | |
virtual param_entry_t * | parameters (void)=0 |
Get pointer to the list of parameters. |
Onboard parameters base class.
This class is abstract and does not contains the task list, use the child class Onboard_parameters_T
Onboard_parameters::Onboard_parameters | ( | File & | file, |
const State & | state, | ||
Mavlink_message_handler & | message_handler, | ||
const Mavlink_stream & | mavlink_stream, | ||
const conf_t & | config | ||
) |
Constructor: Initialisation of the Parameter_Set structure by setting the number of onboard parameter to 0.
file | Pointer to file storage |
state | Pointer to the state structure |
message_handler | Pointer to MAVLink message handler |
mavlink_stream | Pointer to MAVLink stream |
config | Configuration |
bool Onboard_parameters::add | ( | uint32_t * | val, |
const char * | param_name | ||
) |
Register parameter in the internal parameter list that gets published to MAVlink.
val | Unsigned 32 - bits integer parameter value |
param_name | Name of the parameter |
bool Onboard_parameters::add | ( | int32_t * | val, |
const char * | param_name | ||
) |
Register parameter in the internal parameter list that gets published to MAVlink.
val | Signed 32 - bits integer parameter value |
param_name | Name of the parameter |
bool Onboard_parameters::add | ( | float * | val, |
const char * | param_name | ||
) |
Registers parameter in the internal parameter list that gets published to MAVlink.
val | Floating point parameter value |
param_name | Name of the parameter |
Onboard_parameters::conf_t Onboard_parameters::default_config | ( | void | ) | [inline, static] |
Default configuration.
virtual uint32_t Onboard_parameters::max_count | ( | void | ) | [protected, pure virtual] |
Get maximum number of parameters.
Abstract method to be implemented in child classes
Implemented in Onboard_parameters_T< N >, and Onboard_parameters_T< N_PARAM >.
virtual param_entry_t* Onboard_parameters::parameters | ( | void | ) | [protected, pure virtual] |
Get pointer to the list of parameters.
Abstract method to be implemented in child classes
Implemented in Onboard_parameters_T< N >, and Onboard_parameters_T< N_PARAM >.
Read onboard parameters from the file storage.
bool Onboard_parameters::send_first_scheduled_parameter | ( | void | ) |
Searches through the list of parameters, and send only the first scheduled parameter.
bool Onboard_parameters::write_to_storage | ( | ) |
Write onboard parameters to the file storage.