mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: move constructor and complex accessors to cpp file
These functions are slightly long and make the .h file hard to read. Also saves a small amount of flash space. No functional change
This commit is contained in:
parent
0066022a7f
commit
3172657f26
@ -242,6 +242,12 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
// constructor
|
||||
AP_GPS::AP_GPS()
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
/// Startup initialisation.
|
||||
void AP_GPS::init(DataFlash_Class *dataflash, const AP_SerialManager& serial_manager)
|
||||
{
|
||||
@ -266,10 +272,48 @@ void AP_GPS::init(DataFlash_Class *dataflash, const AP_SerialManager& serial_man
|
||||
|
||||
// baudrates to try to detect GPSes with
|
||||
const uint32_t AP_GPS::_baudrates[] = {4800U, 19200U, 38400U, 115200U, 57600U, 9600U, 230400U};
|
||||
// return number of active GPS sensors. Note that if the first GPS
|
||||
// is not present but the 2nd is then we return 2. Note that a blended
|
||||
// GPS solution is treated as an additional sensor.
|
||||
uint8_t AP_GPS::num_sensors(void) const
|
||||
{
|
||||
if (!_output_is_blended) {
|
||||
return num_instances;
|
||||
} else {
|
||||
return num_instances+1;
|
||||
}
|
||||
}
|
||||
|
||||
// initialisation blobs to send to the GPS to try to get it into the
|
||||
// right mode
|
||||
const char AP_GPS::_initialisation_blob[] = UBLOX_SET_BINARY MTK_SET_BINARY SIRF_SET_BINARY;
|
||||
bool AP_GPS::speed_accuracy(uint8_t instance, float &sacc) const
|
||||
{
|
||||
if (state[instance].have_speed_accuracy) {
|
||||
sacc = state[instance].speed_accuracy;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool AP_GPS::horizontal_accuracy(uint8_t instance, float &hacc) const
|
||||
{
|
||||
if (state[instance].have_horizontal_accuracy) {
|
||||
hacc = state[instance].horizontal_accuracy;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool AP_GPS::vertical_accuracy(uint8_t instance, float &vacc) const
|
||||
{
|
||||
if (state[instance].have_vertical_accuracy) {
|
||||
vacc = state[instance].vertical_accuracy;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
convert GPS week and milliseconds to unix epoch in milliseconds
|
||||
@ -996,6 +1040,17 @@ float AP_GPS::get_lag(uint8_t instance) const
|
||||
}
|
||||
}
|
||||
|
||||
// return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin
|
||||
const Vector3f &AP_GPS::get_antenna_offset(uint8_t instance) const
|
||||
{
|
||||
if (instance == GPS_MAX_RECEIVERS) {
|
||||
// return an offset for the blended GPS solution
|
||||
return _blended_antenna_offset;
|
||||
} else {
|
||||
return _antenna_offset[instance];
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
return gps update rate in milliseconds
|
||||
*/
|
||||
|
@ -46,10 +46,6 @@ class AP_GPS_Backend;
|
||||
class AP_GPS
|
||||
{
|
||||
public:
|
||||
// constructor
|
||||
AP_GPS() {
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
/// Startup initialisation.
|
||||
void init(DataFlash_Class *dataflash, const AP_SerialManager& serial_manager);
|
||||
@ -58,6 +54,8 @@ public:
|
||||
/// This routine must be called periodically (typically at 10Hz or
|
||||
/// more) to process incoming data.
|
||||
void update(void);
|
||||
// constructor
|
||||
AP_GPS();
|
||||
|
||||
// GPS driver types
|
||||
enum GPS_Type {
|
||||
@ -144,13 +142,7 @@ public:
|
||||
// return number of active GPS sensors. Note that if the first GPS
|
||||
// is not present but the 2nd is then we return 2. Note that a blended
|
||||
// GPS solution is treated as an additional sensor.
|
||||
uint8_t num_sensors(void) const {
|
||||
if (!_output_is_blended) {
|
||||
return num_instances;
|
||||
} else {
|
||||
return num_instances+1;
|
||||
}
|
||||
}
|
||||
uint8_t num_sensors(void) const;
|
||||
|
||||
// Return the index of the primary sensor which is the index of the sensor contributing to
|
||||
// the output. A blended solution is available as an additional instance
|
||||
@ -177,38 +169,18 @@ public:
|
||||
return location(primary_instance);
|
||||
}
|
||||
|
||||
bool speed_accuracy(uint8_t instance, float &sacc) const {
|
||||
if(state[instance].have_speed_accuracy) {
|
||||
sacc = state[instance].speed_accuracy;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// report speed accuracy
|
||||
bool speed_accuracy(uint8_t instance, float &sacc) const;
|
||||
bool speed_accuracy(float &sacc) const {
|
||||
return speed_accuracy(primary_instance, sacc);
|
||||
}
|
||||
|
||||
bool horizontal_accuracy(uint8_t instance, float &hacc) const {
|
||||
if(state[instance].have_horizontal_accuracy) {
|
||||
hacc = state[instance].horizontal_accuracy;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool horizontal_accuracy(uint8_t instance, float &hacc) const;
|
||||
bool horizontal_accuracy(float &hacc) const {
|
||||
return horizontal_accuracy(primary_instance, hacc);
|
||||
}
|
||||
|
||||
bool vertical_accuracy(uint8_t instance, float &vacc) const {
|
||||
if(state[instance].have_vertical_accuracy) {
|
||||
vacc = state[instance].vertical_accuracy;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool vertical_accuracy(uint8_t instance, float &vacc) const;
|
||||
bool vertical_accuracy(float &vacc) const {
|
||||
return vertical_accuracy(primary_instance, vacc);
|
||||
}
|
||||
@ -332,14 +304,7 @@ public:
|
||||
uint16_t get_rate_ms(uint8_t instance) const;
|
||||
|
||||
// return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin
|
||||
const Vector3f &get_antenna_offset(uint8_t instance) const {
|
||||
if (instance == GPS_MAX_RECEIVERS) {
|
||||
// return an offset for the blended GPS solution
|
||||
return _blended_antenna_offset;
|
||||
} else {
|
||||
return _antenna_offset[instance];
|
||||
}
|
||||
}
|
||||
const Vector3f &get_antenna_offset(uint8_t instance) const;
|
||||
|
||||
// set position for HIL
|
||||
void setHIL(uint8_t instance, GPS_Status status, uint64_t time_epoch_ms,
|
||||
|
Loading…
Reference in New Issue
Block a user