AP_OpticalFlow: rename BUS_ID parameter to ADDR

This makes the parameter more consistent with RangeFinder
This commit is contained in:
Randy Mackay 2017-08-22 11:23:18 +09:00
parent c1e9a30c1d
commit ac36193481
4 changed files with 9 additions and 9 deletions

View File

@ -62,7 +62,7 @@ bool AP_OpticalFlow_PX4Flow::scan_buses(void)
continue;
}
#endif
AP_HAL::OwnPtr<AP_HAL::Device> tdev = hal.i2c_mgr->get_device(bus, PX4FLOW_BASE_I2C_ADDR + get_bus_id());
AP_HAL::OwnPtr<AP_HAL::Device> 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();

View File

@ -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
};

View File

@ -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;

View File

@ -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;