AP_GPS: change UAVCAN in metadata to DroneCAN
This commit is contained in:
parent
8ddb12d9cb
commit
35cc90d117
@ -79,7 +79,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @Param: _TYPE
|
||||
// @DisplayName: 1st GPS type
|
||||
// @Description: GPS type of 1st GPS
|
||||
// @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:UAVCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:UAVCAN-MovingBaseline-Base,23:UAVCAN-MovingBaseline-Rover
|
||||
// @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:DroneCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:DroneCAN-MovingBaseline-Base,23:DroneCAN-MovingBaseline-Rover
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_TYPE", 0, AP_GPS, _type[0], HAL_GPS_TYPE_DEFAULT),
|
||||
@ -88,7 +88,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @Param: _TYPE2
|
||||
// @DisplayName: 2nd GPS type
|
||||
// @Description: GPS type of 2nd GPS
|
||||
// @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:UAVCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:UAVCAN-MovingBaseline-Base,23:UAVCAN-MovingBaseline-Rover
|
||||
// @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:DroneCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:DroneCAN-MovingBaseline-Base,23:DroneCAN-MovingBaseline-Rover
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_TYPE2", 1, AP_GPS, _type[1], 0),
|
||||
@ -181,7 +181,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @Param: _AUTO_CONFIG
|
||||
// @DisplayName: Automatic GPS configuration
|
||||
// @Description: Controls if the autopilot should automatically configure the GPS based on the parameters and default settings
|
||||
// @Values: 0:Disables automatic configuration,1:Enable automatic configuration for Serial GPSes only,2:Enable automatic configuration for UAVCAN as well
|
||||
// @Values: 0:Disables automatic configuration,1:Enable automatic configuration for Serial GPSes only,2:Enable automatic configuration for DroneCAN as well
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_AUTO_CONFIG", 13, AP_GPS, _auto_config, 1),
|
||||
|
||||
@ -364,14 +364,14 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
AP_GROUPINFO("_CAN_NODEID2", 29, AP_GPS, _node_id[1], 0),
|
||||
#endif // GPS_MAX_RECEIVERS > 1
|
||||
// @Param: 1_CAN_OVRIDE
|
||||
// @DisplayName: First UAVCAN GPS NODE ID
|
||||
// @DisplayName: First DroneCAN GPS NODE ID
|
||||
// @Description: GPS Node id for first GPS. If 0 the gps will be automatically selected on first come basis.
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("1_CAN_OVRIDE", 30, AP_GPS, _override_node_id[0], 0),
|
||||
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
// @Param: 2_CAN_OVRIDE
|
||||
// @DisplayName: Second UAVCAN GPS NODE ID
|
||||
// @DisplayName: Second DroneCAN GPS NODE ID
|
||||
// @Description: GPS Node id for second GPS. If 0 the gps will be automatically selected on first come basis.
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("2_CAN_OVRIDE", 31, AP_GPS, _override_node_id[1], 0),
|
||||
|
Loading…
Reference in New Issue
Block a user