Browse Source

params: make param_t uint16_t on NuttX

param_t is only used as an offset and we have <1000 params, so an uint16_t
is enough.
This saves roughly 1KB of RAM. We only do that on NuttX because normal
integers have better performance in general.
Previously on amd64, this was even 64bits because it was an uintptr_t.
sbg
Beat Küng 8 years ago committed by Lorenz Meier
parent
commit
b4290b6b52
  1. 2
      src/modules/systemlib/flashparams/flashparams.c
  2. 2
      src/modules/systemlib/param/param.c
  3. 35
      src/modules/systemlib/param/param.h
  4. 2
      src/modules/systemlib/param/param_shmem.c
  5. 2
      src/platforms/posix/px4_layer/shmem_posix.c
  6. 2
      src/platforms/qurt/px4_layer/shmem_qurt.c
  7. 2
      src/systemcmds/param/param.c
  8. 4
      unittests/param_test.cpp

2
src/modules/systemlib/flashparams/flashparams.c

@ -65,8 +65,8 @@ @@ -65,8 +65,8 @@
* Storage for modified parameters.
*/
struct param_wbuf_s {
param_t param;
union param_value_u val;
param_t param;
bool unsaved;
};

2
src/modules/systemlib/param/param.c

@ -111,8 +111,8 @@ static const struct param_info_s *param_info_base = (const struct param_info_s * @@ -111,8 +111,8 @@ static const struct param_info_s *param_info_base = (const struct param_info_s *
* Storage for modified parameters.
*/
struct param_wbuf_s {
param_t param;
union param_value_u val;
param_t param;
bool unsaved;
};

35
src/modules/systemlib/param/param.h

@ -69,23 +69,50 @@ typedef enum param_type_e { @@ -69,23 +69,50 @@ typedef enum param_type_e {
PARAM_TYPE_UNKNOWN = 0xffff
} param_type_t;
#ifdef __PX4_NUTTX // on NuttX use 16 bits to save RAM
/**
* Parameter handle.
*
* Parameters are represented by parameter handles, which can
* be obtained by looking up parameters. They are an offset into a global
* constant parameter array.
*/
typedef uint16_t param_t;
/**
* Handle returned when a parameter cannot be found.
*/
#define PARAM_INVALID ((uint16_t)0xffff)
/**
* Magic handle for hash check param
*/
#define PARAM_HASH ((uint16_t)INT16_MAX)
#else // on other platforms use 32 bits for better performance
/**
* Parameter handle.
*
* Parameters are represented by parameter handles, which can
* be obtained by looking up (or creating?) parameters.
* be obtained by looking up parameters. They are an offset into a global
* constant parameter array.
*/
typedef uintptr_t param_t;
typedef uint32_t param_t;
/**
* Handle returned when a parameter cannot be found.
*/
#define PARAM_INVALID ((uintptr_t)0xffffffff)
#define PARAM_INVALID ((uint32_t)0xffffffff)
/**
* Magic handle for hash check param
*/
#define PARAM_HASH ((uintptr_t)INT32_MAX)
#define PARAM_HASH ((uint32_t)INT32_MAX)
#endif /* __PX4_NUTTX */
/**
* Initialize the param backend. Call this on startup before calling any other methods.

2
src/modules/systemlib/param/param_shmem.c

@ -96,8 +96,8 @@ static struct param_info_s *param_info_base = (struct param_info_s *) &px4_param @@ -96,8 +96,8 @@ static struct param_info_s *param_info_base = (struct param_info_s *) &px4_param
* Storage for modified parameters.
*/
struct param_wbuf_s {
param_t param;
union param_value_u val;
param_t param;
bool unsaved;
};

2
src/platforms/posix/px4_layer/shmem_posix.c

@ -61,8 +61,8 @@ uint64_t update_from_shmem_prev_time = 0, update_from_shmem_current_time = 0; @@ -61,8 +61,8 @@ uint64_t update_from_shmem_prev_time = 0, update_from_shmem_current_time = 0;
extern unsigned char *adsp_changed_index;
struct param_wbuf_s {
param_t param;
union param_value_u val;
param_t param;
bool unsaved;
};

2
src/platforms/qurt/px4_layer/shmem_qurt.c

@ -77,8 +77,8 @@ static unsigned log2_for_int(unsigned v) @@ -77,8 +77,8 @@ static unsigned log2_for_int(unsigned v)
}
struct param_wbuf_s {
param_t param;
union param_value_u val;
param_t param;
bool unsaved;
};
extern struct param_wbuf_s *param_find_changed(param_t param);

2
src/systemcmds/param/param.c

@ -368,7 +368,7 @@ do_find(const char *name) @@ -368,7 +368,7 @@ do_find(const char *name)
return 1;
}
PARAM_PRINT("Found param %s at index %" PRIxPTR "\n", name, ret);
PARAM_PRINT("Found param %s at index %i\n", name, (int)ret);
return 0;
}

4
unittests/param_test.cpp

@ -54,8 +54,8 @@ void _assert_parameter_int_value(param_t param, int32_t expected) @@ -54,8 +54,8 @@ void _assert_parameter_int_value(param_t param, int32_t expected)
{
int32_t value;
int result = param_get(param, &value);
ASSERT_EQ(0, result) << printf("param_get (%lu) did not return parameter\n", param);
ASSERT_EQ(expected, value) << printf("value for param (%lu) doesn't match default value\n", param);
ASSERT_EQ(0, result) << printf("param_get (%i) did not return parameter\n", (int)param);
ASSERT_EQ(expected, value) << printf("value for param (%i) doesn't match default value\n", (int)param);
}
void _set_all_int_parameters_to(int32_t value)

Loading…
Cancel
Save