AP_GPS: Add parameters defining antenna offset in body frame

This commit is contained in:
priseborough 2016-10-08 09:04:14 +11:00 committed by Andrew Tridgell
parent 0d1e50b50b
commit b51c9dea6c
2 changed files with 48 additions and 1 deletions

View File

@ -153,6 +153,44 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
// @User: Advanced
AP_GROUPINFO("RATE_MS2", 15, AP_GPS, _rate_ms[1], 200),
// @Param: POS1_X
// @DisplayName: Antenna X position offset
// @Description: X position of the first GPS antenna in body frame. Use antenna phase centroid location if provided by the manufacturer.
// @Units: m
// @User: Advanced
// @Param: POS1_Y
// @DisplayName: Antenna Y position offset
// @Description: Y position of the first GPS antenna in body frame. Use antenna phase centroid location if provided by the manufacturer.
// @Units: m
// @User: Advanced
// @Param: POS1_Z
// @DisplayName: Antenna Z position offset
// @Description: Z position of the first GPS antenna in body frame. Use antenna phase centroid location if provided by the manufacturer.
// @Units: m
// @User: Advanced
AP_GROUPINFO("POS1", 16, AP_GPS, _antenna_offset[0], 0.0f),
// @Param: POS2_X
// @DisplayName: Antenna X position offset
// @Description: X position of the second GPS antenna in body frame. Use antenna phase centroid location if provided by the manufacturer.
// @Units: m
// @User: Advanced
// @Param: POS2_Y
// @DisplayName: Antenna Y position offset
// @Description: Y position of the second GPS antenna in body frame. Use antenna phase centroid location if provided by the manufacturer.
// @Units: m
// @User: Advanced
// @Param: POS2_Z
// @DisplayName: Antenna Z position offset
// @Description: Z position of the second GPS antenna in body frame. Use antenna phase centroid location if provided by the manufacturer.
// @Units: m
// @User: Advanced
AP_GROUPINFO("POS2", 17, AP_GPS, _antenna_offset[1], 0.0f),
AP_GROUPEND
};

View File

@ -312,6 +312,14 @@ public:
// the expected lag (in seconds) in the position and velocity readings from the gps
float get_lag() const { return 0.2f; }
// return a 3D vector defining the offset of the GPS antenna in metres relative to the body frame origin
const Vector3f get_antenna_offset(uint8_t instance) const {
return _antenna_offset[instance];
}
const Vector3f get_antenna_offset(void) const {
return _antenna_offset[primary_instance];
}
// set position for HIL
void setHIL(uint8_t instance, GPS_Status status, uint64_t time_epoch_ms,
const Location &location, const Vector3f &velocity, uint8_t num_sats,
@ -340,7 +348,8 @@ public:
AP_Int16 _rate_ms[2];
AP_Int8 _save_config;
AP_Int8 _auto_config;
AP_Vector3f _antenna_offset[2];
// handle sending of initialisation strings to the GPS
void send_blob_start(uint8_t instance, const char *_blob, uint16_t size);
void send_blob_update(uint8_t instance);