MAV'RIC
Classes | Public Member Functions | Static Public Member Functions | Protected Member Functions
Onboard_parameters Class Reference

Onboard parameters base class. More...

#include <onboard_parameters.hpp>

Inheritance diagram for Onboard_parameters:
Inheritance graph
[legend]

List of all members.

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_tparameters (void)=0
 Get pointer to the list of parameters.

Detailed Description

Onboard parameters base class.

This class is abstract and does not contains the task list, use the child class Onboard_parameters_T


Constructor & Destructor Documentation

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.

Parameters:
filePointer to file storage
statePointer to the state structure
message_handlerPointer to MAVLink message handler
mavlink_streamPointer to MAVLink stream
configConfiguration
Returns:
True if the init succeed, false otherwise

Here is the call graph for this function:


Member Function Documentation

bool Onboard_parameters::add ( uint32_t *  val,
const char *  param_name 
)

Register parameter in the internal parameter list that gets published to MAVlink.

Parameters:
valUnsigned 32 - bits integer parameter value
param_nameName of the parameter
Returns:
True if the parameter was added, false otherwise

Here is the call graph for this function:

bool Onboard_parameters::add ( int32_t *  val,
const char *  param_name 
)

Register parameter in the internal parameter list that gets published to MAVlink.

Parameters:
valSigned 32 - bits integer parameter value
param_nameName of the parameter
Returns:
True if the parameter was added, false otherwise

Here is the call graph for this function:

bool Onboard_parameters::add ( float *  val,
const char *  param_name 
)

Registers parameter in the internal parameter list that gets published to MAVlink.

Parameters:
valFloating point parameter value
param_nameName of the parameter
Returns:
True if the parameter was added, false otherwise

Here is the call graph for this function:

Default configuration.

Returns:
Config
virtual uint32_t Onboard_parameters::max_count ( void  ) [protected, pure virtual]

Get maximum number of parameters.

Abstract method to be implemented in child classes

Returns:
Maximum number of parameters

Implemented in Onboard_parameters_T< N >, and Onboard_parameters_T< N_PARAM >.

Here is the caller graph for this function:

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

Returns:
task list

Implemented in Onboard_parameters_T< N >, and Onboard_parameters_T< N_PARAM >.

Here is the caller graph for this function:

Read onboard parameters from the file storage.

Returns:
The result of the read procedure

Here is the call graph for this function:

Here is the caller graph for this function:

Searches through the list of parameters, and send only the first scheduled parameter.

Returns:
success

Here is the call graph for this function:

Here is the caller graph for this function:

Write onboard parameters to the file storage.

Returns:
The result of the write procedure

Here is the call graph for this function:

Here is the caller graph for this function:


The documentation for this class was generated from the following files:
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines