mirror of https://github.com/ArduPilot/ardupilot
AP_Param: moved AP_Vector3f and AP_Matrix3f declarations to AP_Math.h
this avoids us needing AP_Math.h in every utility sketch and example
This commit is contained in:
parent
3bb84bb40c
commit
2b8f0c3a48
|
@ -15,6 +15,7 @@
|
||||||
|
|
||||||
#include <FastSerial.h>
|
#include <FastSerial.h>
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
|
@ -18,7 +18,6 @@
|
||||||
|
|
||||||
#include <avr/pgmspace.h>
|
#include <avr/pgmspace.h>
|
||||||
#include <avr/eeprom.h>
|
#include <avr/eeprom.h>
|
||||||
#include <AP_Math.h>
|
|
||||||
|
|
||||||
#define AP_MAX_NAME_SIZE 15
|
#define AP_MAX_NAME_SIZE 15
|
||||||
|
|
||||||
|
@ -431,13 +430,12 @@ AP_PARAMDEF(int8_t, Int8, AP_PARAM_INT8); // defines AP_Int8
|
||||||
AP_PARAMDEF(int16_t, Int16, AP_PARAM_INT16); // defines AP_Int16
|
AP_PARAMDEF(int16_t, Int16, AP_PARAM_INT16); // defines AP_Int16
|
||||||
AP_PARAMDEF(int32_t, Int32, AP_PARAM_INT32); // defines AP_Int32
|
AP_PARAMDEF(int32_t, Int32, AP_PARAM_INT32); // defines AP_Int32
|
||||||
|
|
||||||
#define AP_PARAMDEFV(_t, _n, _pt) typedef AP_ParamV<_t, _pt> AP_##_n;
|
|
||||||
AP_PARAMDEFV(Matrix3f, Matrix3f, AP_PARAM_MATRIX3F);
|
|
||||||
AP_PARAMDEFV(Vector3f, Vector3f, AP_PARAM_VECTOR3F);
|
|
||||||
|
|
||||||
#define AP_PARAMDEFA(_t, _n, _size, _pt) typedef AP_ParamA<_t, _size, _pt> AP_##_n;
|
#define AP_PARAMDEFA(_t, _n, _size, _pt) typedef AP_ParamA<_t, _size, _pt> AP_##_n;
|
||||||
AP_PARAMDEFA(float, Vector6f, 6, AP_PARAM_VECTOR6F);
|
AP_PARAMDEFA(float, Vector6f, 6, AP_PARAM_VECTOR6F);
|
||||||
|
|
||||||
|
// this is used in AP_Math.h
|
||||||
|
#define AP_PARAMDEFV(_t, _n, _pt) typedef AP_ParamV<_t, _pt> AP_##_n;
|
||||||
|
|
||||||
/// Rely on built in casting for other variable types
|
/// Rely on built in casting for other variable types
|
||||||
/// to minimize template creation and save memory
|
/// to minimize template creation and save memory
|
||||||
#define AP_Uint8 AP_Int8
|
#define AP_Uint8 AP_Int8
|
||||||
|
|
|
@ -2,8 +2,13 @@
|
||||||
|
|
||||||
// Assorted useful math operations for ArduPilot(Mega)
|
// Assorted useful math operations for ArduPilot(Mega)
|
||||||
|
|
||||||
|
#include <AP_Common.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include "vector2.h"
|
#include "vector2.h"
|
||||||
#include "vector3.h"
|
#include "vector3.h"
|
||||||
#include "matrix3.h"
|
#include "matrix3.h"
|
||||||
#include "polygon.h"
|
#include "polygon.h"
|
||||||
|
|
||||||
|
// define AP_Param types AP_Vector3f and Ap_Matrix3f
|
||||||
|
AP_PARAMDEFV(Matrix3f, Matrix3f, AP_PARAM_MATRIX3F);
|
||||||
|
AP_PARAMDEFV(Vector3f, Vector3f, AP_PARAM_VECTOR3F);
|
||||||
|
|
Loading…
Reference in New Issue