43 #ifndef ONBOARD_PARAMETERS_H_
44 #define ONBOARD_PARAMETERS_H_
50 #include "mavlink_stream.h"
51 #include "mavlink_message_handler.h"
52 #include "scheduler.h"
56 #define MAX_ONBOARD_PARAM_COUNT 120 // should be < 122 to fit on user page on AT32UC3C1512
58 #define MAVERIC_FLASHC_USER_PAGE_START_ADDRESS (AVR32_FLASHC_USER_PAGE_ADDRESS + 0x04) // +4bytes for unknown reason
59 #define MAVERIC_FLASHC_USER_PAGE_FREE_SPACE 500 // 512bytes user page,
69 char param_name[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN];
121 float values[MAX_ONBOARD_PARAM_COUNT];
147 bool onboard_parameters_add_parameter_uint32(
onboard_parameters_t* onboard_parameters, uint32_t* val,
const char* param_name);
159 bool onboard_parameters_add_parameter_int32(
onboard_parameters_t* onboard_parameters, int32_t* val,
const char* param_name);
171 bool onboard_parameters_add_parameter_float(
onboard_parameters_t* onboard_parameters,
float* val,
const char* param_name);
TODO: Modify the name of this structure to make it sized as the free flash memory to store these para...
Definition: onboard_parameters.h:118
Main message handler structure.
Definition: mavlink_message_handler.h:152
const mavlink_stream_t * mavlink_stream
Pointer to mavlink_stream.
Definition: onboard_parameters.h:99
float * param
Pointer to the parameter value.
Definition: onboard_parameters.h:68
Definition: mavlink_msg_command_long.h:5
Structure of onboard parameter.
Definition: onboard_parameters.h:66
uint32_t max_param_count
Maximum number of parameters.
Definition: onboard_parameters.h:110
Scheduler.
Definition: scheduler.h:171
Set of onboard parameters.
Definition: onboard_parameters.h:83
uint8_t param_name_length
Length of the parameter name.
Definition: onboard_parameters.h:71
mavlink_message_type_t data_type
Parameter type.
Definition: onboard_parameters.h:70
uint32_t param_count
Number of onboard parameter effectively in the array.
Definition: onboard_parameters.h:85
onboard_parameters_set_t * param_set
Pointer to a set of parameters, needs memory allocation.
Definition: onboard_parameters.h:101
uint32_t max_param_count
Maximum number of parameters.
Definition: onboard_parameters.h:86
bool debug
Indicates if debug messages should be printed for each param change.
Definition: onboard_parameters.h:111
Main structure of the module onboard parameters.
Definition: onboard_parameters.h:97
bool debug
Indicates if debug messages should be printed for each param change.
Definition: onboard_parameters.h:100
Configuration for the module onboard parameters.
Definition: onboard_parameters.h:108
bool schedule_for_transmission
Boolean to activate the transmission of the parameter.
Definition: onboard_parameters.h:73
uint8_t param_id
Parameter ID.
Definition: onboard_parameters.h:72
Main structure for the MAVLink stream module.
Definition: mavlink_stream.h:87