mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Added a union for casting floats to ints and back when storing Floats to the DataFlash
This commit is contained in:
parent
090f5aaa6f
commit
e22832a832
@ -488,6 +488,12 @@ static const float radius_of_earth = 6378100; // meters
|
|||||||
// Used by Mavlink for unknow reasons
|
// Used by Mavlink for unknow reasons
|
||||||
static const float gravity = 9.81; // meters/ sec^2
|
static const float gravity = 9.81; // meters/ sec^2
|
||||||
|
|
||||||
|
// Unions for getting byte values
|
||||||
|
union float_int{
|
||||||
|
int32_t int_value;
|
||||||
|
float float_value;
|
||||||
|
} float_int;
|
||||||
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Location & Navigation
|
// Location & Navigation
|
||||||
|
@ -43,6 +43,19 @@ const struct Menu::command log_menu_commands[] PROGMEM = {
|
|||||||
{"disable", select_logs}
|
{"disable", select_logs}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
static int32_t get_int(float f)
|
||||||
|
{
|
||||||
|
float_int.float_value = f;
|
||||||
|
return float_int.int_value;
|
||||||
|
}
|
||||||
|
|
||||||
|
static float get_float(int32_t i)
|
||||||
|
{
|
||||||
|
float_int.int_value = i;
|
||||||
|
return float_int.float_value;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// A Macro to create the Menu
|
// A Macro to create the Menu
|
||||||
MENU2(log_menu, "Log", log_menu_commands, print_log_menu);
|
MENU2(log_menu, "Log", log_menu_commands, print_log_menu);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user