mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AP_Periph: use AP_PERIPH_RANGEFINDER_PORT_DEFAULT
This commit is contained in:
parent
cfcdc1e78f
commit
0339f09b07
@ -10,8 +10,8 @@ extern const AP_HAL::HAL &hal;
|
|||||||
#define HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT 115200
|
#define HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT 115200
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_PERIPH_RANGEFINDER_PORT_DEFAULT
|
#ifndef AP_PERIPH_RANGEFINDER_PORT_DEFAULT
|
||||||
#define HAL_PERIPH_RANGEFINDER_PORT_DEFAULT 3
|
#define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 3
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_PERIPH_GPS_PORT_DEFAULT
|
#ifndef HAL_PERIPH_GPS_PORT_DEFAULT
|
||||||
@ -239,7 +239,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
GSCALAR(rangefinder_port, "RNGFND_PORT", HAL_PERIPH_RANGEFINDER_PORT_DEFAULT),
|
GSCALAR(rangefinder_port, "RNGFND_PORT", AP_PERIPH_RANGEFINDER_PORT_DEFAULT),
|
||||||
|
|
||||||
// Rangefinder driver
|
// Rangefinder driver
|
||||||
// @Group: RNGFND
|
// @Group: RNGFND
|
||||||
|
Loading…
Reference in New Issue
Block a user