mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_Param: support up to 16 character parameter names
MAVLink allows for 16 chars, with no null termination if all 16 are used
This commit is contained in:
parent
6fdd8ef954
commit
46473d7a8f
@ -19,7 +19,7 @@
|
|||||||
#include <avr/pgmspace.h>
|
#include <avr/pgmspace.h>
|
||||||
#include <avr/eeprom.h>
|
#include <avr/eeprom.h>
|
||||||
|
|
||||||
#define AP_MAX_NAME_SIZE 15
|
#define AP_MAX_NAME_SIZE 16
|
||||||
#define AP_NESTED_GROUPS_ENABLED
|
#define AP_NESTED_GROUPS_ENABLED
|
||||||
|
|
||||||
// a variant of offsetof() to work around C++ restrictions.
|
// a variant of offsetof() to work around C++ restrictions.
|
||||||
@ -66,7 +66,7 @@ public:
|
|||||||
struct GroupInfo {
|
struct GroupInfo {
|
||||||
uint8_t type; // AP_PARAM_*
|
uint8_t type; // AP_PARAM_*
|
||||||
uint8_t idx; // identifier within the group
|
uint8_t idx; // identifier within the group
|
||||||
const char name[AP_MAX_NAME_SIZE];
|
const char name[AP_MAX_NAME_SIZE+1];
|
||||||
uintptr_t offset; // offset within the object
|
uintptr_t offset; // offset within the object
|
||||||
union {
|
union {
|
||||||
const struct GroupInfo *group_info;
|
const struct GroupInfo *group_info;
|
||||||
@ -75,7 +75,7 @@ public:
|
|||||||
};
|
};
|
||||||
struct Info {
|
struct Info {
|
||||||
uint8_t type; // AP_PARAM_*
|
uint8_t type; // AP_PARAM_*
|
||||||
const char name[AP_MAX_NAME_SIZE];
|
const char name[AP_MAX_NAME_SIZE+1];
|
||||||
uint8_t key; // k_param_*
|
uint8_t key; // k_param_*
|
||||||
void *ptr; // pointer to the variable in memory
|
void *ptr; // pointer to the variable in memory
|
||||||
union {
|
union {
|
||||||
|
Loading…
Reference in New Issue
Block a user