From ac36193481ac5052be38e696c244de3c423e781d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 22 Aug 2017 11:23:18 +0900 Subject: [PATCH] AP_OpticalFlow: rename BUS_ID parameter to ADDR This makes the parameter more consistent with RangeFinder --- libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp | 4 ++-- libraries/AP_OpticalFlow/OpticalFlow.cpp | 8 ++++---- libraries/AP_OpticalFlow/OpticalFlow.h | 2 +- libraries/AP_OpticalFlow/OpticalFlow_backend.h | 4 ++-- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp index f92562e5a9..595fe1fec3 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp @@ -62,7 +62,7 @@ bool AP_OpticalFlow_PX4Flow::scan_buses(void) continue; } #endif - AP_HAL::OwnPtr tdev = hal.i2c_mgr->get_device(bus, PX4FLOW_BASE_I2C_ADDR + get_bus_id()); + AP_HAL::OwnPtr tdev = hal.i2c_mgr->get_device(bus, PX4FLOW_BASE_I2C_ADDR + get_address()); if (!tdev) { continue; } @@ -106,7 +106,7 @@ void AP_OpticalFlow_PX4Flow::timer(void) return; } struct OpticalFlow::OpticalFlow_state state {}; - state.device_id = get_bus_id(); + state.device_id = get_address(); if (frame.integration_timespan > 0) { const Vector2f flowScaler = _flowScaler(); diff --git a/libraries/AP_OpticalFlow/OpticalFlow.cpp b/libraries/AP_OpticalFlow/OpticalFlow.cpp index 9df528dfc0..876181a9a1 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow.cpp @@ -58,12 +58,12 @@ const AP_Param::GroupInfo OpticalFlow::var_info[] = { // @User: Advanced AP_GROUPINFO("_POS", 4, OpticalFlow, _pos_offset, 0.0f), - // @Param: _BUS_ID - // @DisplayName: ID on the bus - // @Description: This is used to select between multiple possible bus IDs for some sensor types. For PX4Flow you can choose 0 to 7 for the 8 possible addresses on the I2C bus. + // @Param: _ADDR + // @DisplayName: Address on the bus + // @Description: This is used to select between multiple possible I2C addresses for some sensor types. For PX4Flow you can choose 0 to 7 for the 8 possible addresses on the I2C bus. // @Range: 0 127 // @User: Advanced - AP_GROUPINFO("_BUS_ID", 5, OpticalFlow, _bus_id, 0), + AP_GROUPINFO("_ADDR", 5, OpticalFlow, _address, 0), AP_GROUPEND }; diff --git a/libraries/AP_OpticalFlow/OpticalFlow.h b/libraries/AP_OpticalFlow/OpticalFlow.h index 0c1fbe87b9..f18e85f192 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.h +++ b/libraries/AP_OpticalFlow/OpticalFlow.h @@ -89,7 +89,7 @@ private: AP_Int16 _flowScalerY; // Y axis flow scale factor correction - parts per thousand AP_Int16 _yawAngle_cd; // yaw angle of sensor X axis with respect to vehicle X axis - centi degrees AP_Vector3f _pos_offset; // position offset of the flow sensor in the body frame - AP_Int8 _bus_id; // ID on bus (some sensors only) + AP_Int8 _address; // address on the bus (allows selecting between 8 possible I2C addresses for px4flow) // state filled in by backend struct OpticalFlow_state _state; diff --git a/libraries/AP_OpticalFlow/OpticalFlow_backend.h b/libraries/AP_OpticalFlow/OpticalFlow_backend.h index fae7283d88..91acb6042d 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow_backend.h +++ b/libraries/AP_OpticalFlow/OpticalFlow_backend.h @@ -54,8 +54,8 @@ protected: // get access to AHRS object AP_AHRS_NavEKF &get_ahrs(void) { return frontend._ahrs; } - // get bus ID parameter - uint8_t get_bus_id(void) const { return frontend._bus_id; } + // get ADDR parameter value + uint8_t get_address(void) const { return frontend._address; } // semaphore for access to shared frontend data AP_HAL::Semaphore *_sem;