From 0193517f30ba3451f90fc3f87b8f25a683f25f46 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Tue, 12 Jul 2016 18:51:50 -0300 Subject: [PATCH] AP_RangeFinder: LightWareI2C: use be16toh While at it remove some trailing whitespaces and little reformats. --- .../AP_RangeFinder_LightWareI2C.cpp | 26 ++++++++++--------- 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp index 330975fa0d..420e6d240f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp @@ -13,25 +13,27 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . */ - #include "AP_RangeFinder_LightWareI2C.h" -#include + #include +#include +#include + extern const AP_HAL::HAL& hal; -/* +/* The constructor also initializes the rangefinder. Note that this constructor is not called until detect() returns true, so we already know that we should setup the rangefinder */ -AP_RangeFinder_LightWareI2C::AP_RangeFinder_LightWareI2C(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr dev) : - AP_RangeFinder_Backend(_ranger, instance, _state), - _dev(std::move(dev)) +AP_RangeFinder_LightWareI2C::AP_RangeFinder_LightWareI2C(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr dev) + : AP_RangeFinder_Backend(_ranger, instance, _state) + , _dev(std::move(dev)) { } -/* +/* detect if a Lightware rangefinder is connected. We'll detect by trying to take a reading on I2C. If we get a result the sensor is there. @@ -54,7 +56,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_LightWareI2C::detect(RangeFinder &_ranger // read - return last value measured by sensor bool AP_RangeFinder_LightWareI2C::get_reading(uint16_t &reading_cm) { - uint8_t buff[2]; + be16_t val; if (ranger._address[state.instance] == 0) { return false; @@ -64,19 +66,19 @@ bool AP_RangeFinder_LightWareI2C::get_reading(uint16_t &reading_cm) if (!_dev->get_semaphore()->take(1)) { return false; } - + // read the high and low byte distance registers - bool ret = _dev->read(buff, sizeof(buff)); + bool ret = _dev->read((uint8_t *) &val, sizeof(val)); if (ret) { // combine results into distance - reading_cm = ((uint16_t)buff[0]) << 8 | buff[1]; + reading_cm = be16toh(val); } _dev->get_semaphore()->give(); return ret; } -/* +/* update the state of the sensor */ void AP_RangeFinder_LightWareI2C::update(void)