AP_HAL_Linux: init SPIDevice speed by default

Else a speed of 0 will be sent at each transfer.
Behaviour has changed when introducing SPIDevice
This commit is contained in:
Julien Beraud 2017-01-16 15:48:35 +01:00 committed by Lucas De Marchi
parent 0b85921505
commit 0d4ca03dcd

View File

@ -209,6 +209,7 @@ SPIDevice::SPIDevice(SPIBus &bus, SPIDesc &device_desc)
{
set_device_bus(_bus.bus);
set_device_address(_desc.subdev);
_speed = _desc.highspeed;
if (_desc.cs_pin != SPI_CS_KERNEL) {
_cs = hal.gpio->channel(_desc.cs_pin);