mirror of https://github.com/ArduPilot/ardupilot
SITL: rename SITL::GPS_GSOF to SITL::GPS_Trimble
This commit is contained in:
parent
a143d2e453
commit
97417a1038
|
@ -18,7 +18,7 @@
|
|||
#include <AP_InternalError/AP_InternalError.h>
|
||||
|
||||
#include "SIM_GPS_FILE.h"
|
||||
#include "SIM_GPS_GSOF.h"
|
||||
#include "SIM_GPS_Trimble.h"
|
||||
#include "SIM_GPS_MSP.h"
|
||||
#include "SIM_GPS_NMEA.h"
|
||||
#include "SIM_GPS_NOVA.h"
|
||||
|
@ -201,9 +201,9 @@ void GPS::check_backend_allocation()
|
|||
break;
|
||||
#endif
|
||||
|
||||
#if AP_SIM_GPS_GSOF_ENABLED
|
||||
case Type::GSOF:
|
||||
backend = new GPS_GSOF(*this, instance);
|
||||
#if AP_SIM_GPS_TRIMBLE_ENABLED
|
||||
case Type::TRIMBLE:
|
||||
backend = new GPS_Trimble(*this, instance);
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -114,8 +114,8 @@ public:
|
|||
#if AP_SIM_GPS_SBP2_ENABLED
|
||||
SBP2 = 9,
|
||||
#endif
|
||||
#if AP_SIM_GPS_GSOF_ENABLED
|
||||
GSOF = 11, // matches GPS_TYPE
|
||||
#if AP_SIM_GPS_TRIMBLE_ENABLED
|
||||
TRIMBLE = 11, // matches GPS_TYPE
|
||||
#endif
|
||||
#if AP_SIM_GPS_MSP_ENABLED
|
||||
MSP = 19,
|
||||
|
|
|
@ -1,8 +1,8 @@
|
|||
#include "SIM_config.h"
|
||||
|
||||
#if AP_SIM_GPS_GSOF_ENABLED
|
||||
#if AP_SIM_GPS_TRIMBLE_ENABLED
|
||||
|
||||
#include "SIM_GPS_GSOF.h"
|
||||
#include "SIM_GPS_Trimble.h"
|
||||
|
||||
#include <SITL/SITL.h>
|
||||
#include <AP_HAL/utility/sparse-endian.h>
|
||||
|
@ -11,7 +11,7 @@
|
|||
|
||||
using namespace SITL;
|
||||
|
||||
void GPS_GSOF::publish(const GPS_Data *d)
|
||||
void GPS_Trimble::publish(const GPS_Data *d)
|
||||
{
|
||||
// This logic is to populate output buffer only with enabled channels.
|
||||
// It also only sends each channel at the configured rate.
|
||||
|
@ -456,7 +456,7 @@ void DCOL_Parser::reset() {
|
|||
}
|
||||
|
||||
|
||||
void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size)
|
||||
void GPS_Trimble::send_gsof(const uint8_t *buf, const uint16_t size)
|
||||
{
|
||||
// All Trimble "Data Collector" packets, including GSOF, are comprised of three fields:
|
||||
// * A fixed-length packet header (dcol_header)
|
||||
|
@ -532,7 +532,7 @@ void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size)
|
|||
}
|
||||
}
|
||||
|
||||
uint64_t GPS_GSOF::gsof_pack_double(const double& src)
|
||||
uint64_t GPS_Trimble::gsof_pack_double(const double& src)
|
||||
{
|
||||
uint64_t dst;
|
||||
static_assert(sizeof(src) == sizeof(dst));
|
||||
|
@ -541,7 +541,7 @@ uint64_t GPS_GSOF::gsof_pack_double(const double& src)
|
|||
return dst;
|
||||
}
|
||||
|
||||
uint32_t GPS_GSOF::gsof_pack_float(const float& src)
|
||||
uint32_t GPS_Trimble::gsof_pack_float(const float& src)
|
||||
{
|
||||
uint32_t dst;
|
||||
static_assert(sizeof(src) == sizeof(dst));
|
||||
|
@ -550,7 +550,7 @@ uint32_t GPS_GSOF::gsof_pack_float(const float& src)
|
|||
return dst;
|
||||
}
|
||||
|
||||
void GPS_GSOF::update_read() {
|
||||
void GPS_Trimble::update_read() {
|
||||
// Technically, the max command is slightly larger.
|
||||
// This will only slightly slow the response for packets that big.
|
||||
char c[MAX_PAYLOAD_SIZE];
|
||||
|
@ -566,4 +566,4 @@ void GPS_GSOF::update_read() {
|
|||
}
|
||||
}
|
||||
|
||||
#endif // AP_SIM_GPS_GSOF_ENABLED
|
||||
#endif // AP_SIM_GPS_TRIMBLE_ENABLED
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
#include "SIM_config.h"
|
||||
|
||||
#if AP_SIM_GPS_GSOF_ENABLED
|
||||
#if AP_SIM_GPS_TRIMBLE_ENABLED
|
||||
|
||||
#include "SIM_GPS.h"
|
||||
|
||||
|
@ -124,9 +124,9 @@ private:
|
|||
void reset();
|
||||
};
|
||||
|
||||
class GPS_GSOF : public GPS_Backend, public DCOL_Parser {
|
||||
class GPS_Trimble : public GPS_Backend, public DCOL_Parser {
|
||||
public:
|
||||
CLASS_NO_COPY(GPS_GSOF);
|
||||
CLASS_NO_COPY(GPS_Trimble);
|
||||
|
||||
using GPS_Backend::GPS_Backend;
|
||||
|
||||
|
@ -146,4 +146,4 @@ private:
|
|||
|
||||
};
|
||||
|
||||
#endif // AP_SIM_GPS_GSOF_ENABLED
|
||||
#endif // AP_SIM_GPS_TRIMBLE_ENABLED
|
||||
|
|
|
@ -51,8 +51,8 @@
|
|||
#define AP_SIM_GPS_FILE_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX)
|
||||
#endif
|
||||
|
||||
#ifndef AP_SIM_GPS_GSOF_ENABLED
|
||||
#define AP_SIM_GPS_GSOF_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#ifndef AP_SIM_GPS_TRIMBLE_ENABLED
|
||||
#define AP_SIM_GPS_TRIMBLE_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_SIM_GPS_MSP_ENABLED
|
||||
|
|
|
@ -499,7 +499,7 @@ const AP_Param::GroupInfo SIM::var_gps[] = {
|
|||
// @Param: GPS_TYPE
|
||||
// @DisplayName: GPS 1 type
|
||||
// @Description: Sets the type of simulation used for GPS 1
|
||||
// @Values: 0:None, 1:UBlox, 5:NMEA, 6:SBP, 7:File, 8:Nova, 9:SBP, 10:GSOF, 19:MSP
|
||||
// @Values: 0:None, 1:UBlox, 5:NMEA, 6:SBP, 7:File, 8:Nova, 9:SBP, 10:Trimble, 19:MSP
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("GPS_TYPE", 3, SIM, gps_type[0], GPS::Type::UBLOX),
|
||||
// @Param: GPS_BYTELOSS
|
||||
|
|
Loading…
Reference in New Issue