mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Periph: added RNGFND_BAUDRATE
allows control of rangefinder baudrate
This commit is contained in:
parent
2708c99bfb
commit
3884419153
@ -120,6 +120,9 @@ void AP_Periph_FW::init()
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
|
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
|
||||||
|
const uint8_t sernum = 3; // uartB
|
||||||
|
hal.uartB->begin(g.rangefinder_baud);
|
||||||
|
serial_manager.set_protocol_and_baud(sernum, AP_SerialManager::SerialProtocol_Rangefinder, g.rangefinder_baud);
|
||||||
rangefinder.init(ROTATION_NONE);
|
rangefinder.init(ROTATION_NONE);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -197,6 +200,9 @@ void AP_Periph_FW::update()
|
|||||||
#endif
|
#endif
|
||||||
#ifdef HAL_PERIPH_ENABLE_BARO
|
#ifdef HAL_PERIPH_ENABLE_BARO
|
||||||
hal.uartA->printf("BARO H=%u P=%.2f T=%.2f\n", baro.healthy(), baro.get_pressure(), baro.get_temperature());
|
hal.uartA->printf("BARO H=%u P=%.2f T=%.2f\n", baro.healthy(), baro.get_pressure(), baro.get_temperature());
|
||||||
|
#endif
|
||||||
|
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
|
||||||
|
hal.uartA->printf("RNG %u %ucm\n", rangefinder.num_sensors(), rangefinder.distance_cm_orient(ROTATION_NONE));
|
||||||
#endif
|
#endif
|
||||||
hal.scheduler->delay(1);
|
hal.scheduler->delay(1);
|
||||||
show_stack_usage();
|
show_stack_usage();
|
||||||
|
@ -70,6 +70,10 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
GOBJECT(airspeed, "ARSP", AP_Airspeed),
|
GOBJECT(airspeed, "ARSP", AP_Airspeed),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
|
||||||
|
GSCALAR(rangefinder_baud, "RNGFND_BAUDRATE", 115200),
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
|
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
|
||||||
// Rangefinder driver
|
// Rangefinder driver
|
||||||
// @Group: RNGFND
|
// @Group: RNGFND
|
||||||
|
@ -22,6 +22,7 @@ public:
|
|||||||
k_param_airspeed,
|
k_param_airspeed,
|
||||||
k_param_rangefinder,
|
k_param_rangefinder,
|
||||||
k_param_flash_bootloader,
|
k_param_flash_bootloader,
|
||||||
|
k_param_rangefinder_baud,
|
||||||
};
|
};
|
||||||
|
|
||||||
AP_Int16 format_version;
|
AP_Int16 format_version;
|
||||||
@ -38,6 +39,9 @@ public:
|
|||||||
AP_Int8 flash_bootloader;
|
AP_Int8 flash_bootloader;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
|
||||||
|
AP_Int32 rangefinder_baud;
|
||||||
|
#endif
|
||||||
Parameters() {}
|
Parameters() {}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user