AP_GPS: remove check for GPS_MAX_INSTANCES

All supported boards may have more than 1 GPS instance.
This commit is contained in:
Lucas De Marchi 2015-11-03 11:17:25 -02:00 committed by Andrew Tridgell
parent c74b1a660d
commit c75c1d84d9
4 changed files with 23 additions and 72 deletions

View File

@ -33,8 +33,6 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
// @RebootRequired: True
AP_GROUPINFO("TYPE", 0, AP_GPS, _type[0], 1),
#if GPS_MAX_INSTANCES > 1
// @Param: TYPE2
// @DisplayName: 2nd GPS type
// @Description: GPS type of 2nd GPS
@ -42,8 +40,6 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
// @RebootRequired: True
AP_GROUPINFO("TYPE2", 1, AP_GPS, _type[1], 0),
#endif
// @Param: NAVFILTER
// @DisplayName: Navigation filter setting
// @Description: Navigation filter engine setting
@ -51,14 +47,12 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
// @RebootRequired: True
AP_GROUPINFO("NAVFILTER", 2, AP_GPS, _navfilter, GPS_ENGINE_AIRBORNE_4G),
#if GPS_MAX_INSTANCES > 1
// @Param: AUTO_SWITCH
// @DisplayName: Automatic Switchover Setting
// @Description: Automatic switchover to GPS reporting best lock
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO("AUTO_SWITCH", 3, AP_GPS, _auto_switch, 1),
#endif
#if GPS_RTK_AVAILABLE
// @Param: MIN_DGPS
@ -87,16 +81,12 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
// @RebootRequired: True
AP_GROUPINFO("MIN_ELEV", 6, AP_GPS, _min_elevation, -100),
#if GPS_MAX_INSTANCES > 1
// @Param: INJECT_TO
// @DisplayName: Destination for GPS_INJECT_DATA MAVLink packets
// @Description: The GGS can send raw serial packets to inject data to multiple GPSes.
// @Values: 0:send to first GPS, 1:send to 2nd GPS, 127:send to all
AP_GROUPINFO("INJECT_TO", 7, AP_GPS, _inject_to, GPS_RTK_INJECT_TO_ALL),
#endif
#if GPS_RTK_AVAILABLE
// @Param: SBP_LOGMASK
// @DisplayName: Swift Binary Protocol Logging Mask
@ -135,11 +125,8 @@ void AP_GPS::init(DataFlash_Class *dataflash, const AP_SerialManager& serial_man
// search for serial ports with gps protocol
_port[0] = serial_manager.find_serial(AP_SerialManager::SerialProtocol_GPS, 0);
#if GPS_MAX_INSTANCES > 1
_port[1] = serial_manager.find_serial(AP_SerialManager::SerialProtocol_GPS, 1);
_last_instance_swap_ms = 0;
#endif
}
// baudrates to try to detect GPSes with
@ -405,7 +392,6 @@ AP_GPS::update(void)
update_instance(i);
}
#if GPS_MAX_INSTANCES > 1
// work out which GPS is the primary, and how many sensors we have
for (uint8_t i=0; i<GPS_MAX_INSTANCES; i++) {
if (state[i].status != NO_GPS) {
@ -443,9 +429,7 @@ AP_GPS::update(void)
primary_instance = 0;
}
}
#else
num_instances = 1;
#endif // GPS_MAX_INSTANCES
// update notify with gps status. We always base this on the primary_instance
AP_Notify::flags.gps_status = state[primary_instance].status;
}
@ -504,9 +488,6 @@ AP_GPS::lock_port(uint8_t instance, bool lock)
void
AP_GPS::inject_data(uint8_t *data, uint8_t len)
{
#if GPS_MAX_INSTANCES > 1
//Support broadcasting to all GPSes.
if (_inject_to == GPS_RTK_INJECT_TO_ALL) {
for (uint8_t i=0; i<GPS_MAX_INSTANCES; i++) {
@ -515,11 +496,6 @@ AP_GPS::inject_data(uint8_t *data, uint8_t len)
} else {
inject_data(_inject_to, data, len);
}
#else
inject_data(0,data,len);
#endif
}
void
@ -562,7 +538,6 @@ AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
num_sats(0));
}
#if GPS_MAX_INSTANCES > 1
void
AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
{
@ -592,7 +567,6 @@ AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
0,
0);
}
#endif
#if GPS_RTK_AVAILABLE
void
@ -603,7 +577,6 @@ AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan)
}
}
#if GPS_MAX_INSTANCES > 1
void
AP_GPS::send_mavlink_gps2_rtk(mavlink_channel_t chan)
{
@ -612,4 +585,3 @@ AP_GPS::send_mavlink_gps2_rtk(mavlink_channel_t chan)
}
}
#endif
#endif

View File

@ -136,18 +136,9 @@ public:
return primary_instance;
}
// using these macros saves some code space on APM2
#if GPS_MAX_INSTANCES == 1
# define _GPS_STATE(instance) state[0]
# define _GPS_TIMING(instance) timing[0]
#else
# define _GPS_STATE(instance) state[instance]
# define _GPS_TIMING(instance) timing[instance]
#endif
/// Query GPS status
GPS_Status status(uint8_t instance) const {
return _GPS_STATE(instance).status;
return state[instance].status;
}
GPS_Status status(void) const {
return status(primary_instance);
@ -159,15 +150,15 @@ public:
// location of last fix
const Location &location(uint8_t instance) const {
return _GPS_STATE(instance).location;
return state[instance].location;
}
const Location &location() const {
return location(primary_instance);
}
bool speed_accuracy(uint8_t instance, float &sacc) const {
if(_GPS_STATE(instance).have_speed_accuracy) {
sacc = _GPS_STATE(instance).speed_accuracy;
if(state[instance].have_speed_accuracy) {
sacc = state[instance].speed_accuracy;
return true;
}
return false;
@ -178,8 +169,8 @@ public:
}
bool horizontal_accuracy(uint8_t instance, float &hacc) const {
if(_GPS_STATE(instance).have_horizontal_accuracy) {
hacc = _GPS_STATE(instance).horizontal_accuracy;
if(state[instance].have_horizontal_accuracy) {
hacc = state[instance].horizontal_accuracy;
return true;
}
return false;
@ -190,8 +181,8 @@ public:
}
bool vertical_accuracy(uint8_t instance, float &vacc) const {
if(_GPS_STATE(instance).have_vertical_accuracy) {
vacc = _GPS_STATE(instance).vertical_accuracy;
if(state[instance].have_vertical_accuracy) {
vacc = state[instance].vertical_accuracy;
return true;
}
return false;
@ -203,7 +194,7 @@ public:
// 3D velocity in NED format
const Vector3f &velocity(uint8_t instance) const {
return _GPS_STATE(instance).velocity;
return state[instance].velocity;
}
const Vector3f &velocity() const {
return velocity(primary_instance);
@ -211,7 +202,7 @@ public:
// ground speed in m/s
float ground_speed(uint8_t instance) const {
return _GPS_STATE(instance).ground_speed;
return state[instance].ground_speed;
}
float ground_speed() const {
return ground_speed(primary_instance);
@ -224,7 +215,7 @@ public:
// ground course in centidegrees
int32_t ground_course_cd(uint8_t instance) const {
return _GPS_STATE(instance).ground_course_cd;
return state[instance].ground_course_cd;
}
int32_t ground_course_cd() const {
return ground_course_cd(primary_instance);
@ -232,7 +223,7 @@ public:
// number of locked satellites
uint8_t num_sats(uint8_t instance) const {
return _GPS_STATE(instance).num_sats;
return state[instance].num_sats;
}
uint8_t num_sats() const {
return num_sats(primary_instance);
@ -240,7 +231,7 @@ public:
// GPS time of week in milliseconds
uint32_t time_week_ms(uint8_t instance) const {
return _GPS_STATE(instance).time_week_ms;
return state[instance].time_week_ms;
}
uint32_t time_week_ms() const {
return time_week_ms(primary_instance);
@ -248,7 +239,7 @@ public:
// GPS week
uint16_t time_week(uint8_t instance) const {
return _GPS_STATE(instance).time_week;
return state[instance].time_week;
}
uint16_t time_week() const {
return time_week(primary_instance);
@ -256,7 +247,7 @@ public:
// horizontal dilution of precision
uint16_t get_hdop(uint8_t instance) const {
return _GPS_STATE(instance).hdop;
return state[instance].hdop;
}
uint16_t get_hdop() const {
return get_hdop(primary_instance);
@ -264,7 +255,7 @@ public:
// vertical dilution of precision
uint16_t get_vdop(uint8_t instance) const {
return _GPS_STATE(instance).vdop;
return state[instance].vdop;
}
uint16_t get_vdop() const {
return get_vdop(primary_instance);
@ -273,16 +264,16 @@ public:
// the time we got our last fix in system milliseconds. This is
// used when calculating how far we might have moved since that fix
uint32_t last_fix_time_ms(uint8_t instance) const {
return _GPS_TIMING(instance).last_fix_time_ms;
return timing[instance].last_fix_time_ms;
}
uint32_t last_fix_time_ms(void) const {
return last_fix_time_ms(primary_instance);
}
// the time we last processed a message in milliseconds. This is
// used to indicate that we have new GPS data to process
uint32_t last_message_time_ms(uint8_t instance) const {
return _GPS_TIMING(instance).last_message_time_ms;
// the time we last processed a message in milliseconds. This is
// used to indicate that we have new GPS data to process
uint32_t last_message_time_ms(uint8_t instance) const {
return timing[instance].last_message_time_ms;
}
uint32_t last_message_time_ms(void) const {
return last_message_time_ms(primary_instance);
@ -296,7 +287,7 @@ public:
// return true if the GPS supports vertical velocity values
bool have_vertical_velocity(uint8_t instance) const {
return _GPS_STATE(instance).have_vertical_velocity;
return state[instance].have_vertical_velocity;
}
bool have_vertical_velocity(void) const {
return have_vertical_velocity(primary_instance);
@ -318,13 +309,11 @@ public:
// configuration parameters
AP_Int8 _type[GPS_MAX_INSTANCES];
AP_Int8 _navfilter;
#if GPS_MAX_INSTANCES > 1
AP_Int8 _auto_switch;
AP_Int8 _min_dgps;
AP_Int16 _sbp_logmask;
AP_Int8 _inject_to;
uint32_t _last_instance_swap_ms;
#endif
AP_Int8 _sbas_mode;
AP_Int8 _min_elevation;
AP_Int8 _raw_data;
@ -343,16 +332,12 @@ public:
//MAVLink Status Sending
void send_mavlink_gps_raw(mavlink_channel_t chan);
#if GPS_MAX_INSTANCES > 1
void send_mavlink_gps2_raw(mavlink_channel_t chan);
#endif
#if GPS_RTK_AVAILABLE
void send_mavlink_gps_rtk(mavlink_channel_t chan);
#if GPS_MAX_INSTANCES > 1
void send_mavlink_gps2_rtk(mavlink_channel_t chan);
#endif
#endif
private:
struct GPS_timing {

View File

@ -47,12 +47,9 @@ public:
//MAVLink methods
virtual void send_mavlink_gps_rtk(mavlink_channel_t chan) { return ; }
#if GPS_MAX_INSTANCES > 1
virtual void send_mavlink_gps2_rtk(mavlink_channel_t chan) { return ; }
#endif
#endif
protected:
AP_HAL::UARTDriver *port; ///< UART we are attached to
AP_GPS &gps; ///< access to frontend (for parameters)

View File

@ -923,8 +923,6 @@ bool GCS_MAVLINK::send_gps_raw(AP_GPS &gps)
}
#endif
#if GPS_MAX_INSTANCES > 1
if (gps.num_sensors() > 1 && gps.status(1) > AP_GPS::NO_GPS) {
if (comm_get_txspace(chan) >= MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_GPS2_RAW_LEN) {
@ -940,7 +938,6 @@ bool GCS_MAVLINK::send_gps_raw(AP_GPS &gps)
}
#endif
}
#endif
//TODO: Should check what else managed to get through...
return true;