2013-08-29 02:34:34 -03:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
2019-11-10 22:47:38 -04:00
# include "AP_RangeFinder.h"
2014-06-26 23:56:50 -03:00
# include "AP_RangeFinder_analog.h"
2014-06-27 00:39:52 -03:00
# include "AP_RangeFinder_PulsedLightLRF.h"
2014-06-27 01:03:47 -03:00
# include "AP_RangeFinder_MaxsonarI2CXL.h"
2016-04-19 18:32:17 -03:00
# include "AP_RangeFinder_MaxsonarSerialLV.h"
2015-07-06 16:24:06 -03:00
# include "AP_RangeFinder_BBB_PRU.h"
2015-08-28 06:52:34 -03:00
# include "AP_RangeFinder_LightWareI2C.h"
2015-09-07 02:32:06 -03:00
# include "AP_RangeFinder_LightWareSerial.h"
2017-12-11 17:53:28 -04:00
# if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
CONFIG_HAL_BOARD_SUBTYPE = = HAL_BOARD_SUBTYPE_LINUX_DISCO ) & & \
defined ( HAVE_LIBIIO )
2016-04-15 14:31:51 -03:00
# include "AP_RangeFinder_Bebop.h"
2017-12-11 17:53:28 -04:00
# endif
2016-05-03 23:57:07 -03:00
# include "AP_RangeFinder_MAVLink.h"
2016-09-13 00:24:41 -03:00
# include "AP_RangeFinder_LeddarOne.h"
2021-10-18 00:47:20 -03:00
# include "AP_RangeFinder_USD1_Serial.h"
2017-07-28 09:46:52 -03:00
# include "AP_RangeFinder_TeraRangerI2C.h"
2022-08-01 20:44:01 -03:00
# include "AP_RangeFinder_TeraRanger_Serial.h"
2017-03-09 19:38:28 -04:00
# include "AP_RangeFinder_VL53L0X.h"
2018-11-17 07:17:51 -04:00
# include "AP_RangeFinder_VL53L1X.h"
2018-05-14 02:03:08 -03:00
# include "AP_RangeFinder_NMEA.h"
2018-05-16 19:31:22 -03:00
# include "AP_RangeFinder_Wasp.h"
2019-11-01 04:03:17 -03:00
# include "AP_RangeFinder_Benewake_TF02.h"
# include "AP_RangeFinder_Benewake_TF03.h"
# include "AP_RangeFinder_Benewake_TFMini.h"
2019-04-26 04:23:45 -03:00
# include "AP_RangeFinder_Benewake_TFMiniPlus.h"
2018-08-29 11:18:49 -03:00
# include "AP_RangeFinder_PWM.h"
2020-06-14 03:11:25 -03:00
# include "AP_RangeFinder_GYUS42v2.h"
2020-05-17 03:41:50 -03:00
# include "AP_RangeFinder_HC_SR04.h"
2022-03-12 06:37:29 -04:00
# include "AP_RangeFinder_Bebop.h"
2019-03-28 09:43:23 -03:00
# include "AP_RangeFinder_BLPing.h"
2019-04-08 06:42:46 -03:00
# include "AP_RangeFinder_UAVCAN.h"
2019-08-31 08:21:01 -03:00
# include "AP_RangeFinder_Lanbao.h"
2020-01-13 01:48:57 -04:00
# include "AP_RangeFinder_LeddarVu8.h"
2020-07-17 20:36:47 -03:00
# include "AP_RangeFinder_SITL.h"
2020-08-04 17:42:19 -03:00
# include "AP_RangeFinder_MSP.h"
2020-12-31 20:10:39 -04:00
# include "AP_RangeFinder_USD1_CAN.h"
2021-11-12 06:11:48 -04:00
# include "AP_RangeFinder_Benewake_CAN.h"
2023-02-15 03:12:26 -04:00
# include "AP_RangeFinder_Lua.h"
2012-01-10 19:44:04 -04:00
2019-07-09 03:14:52 -03:00
# include <AP_BoardConfig/AP_BoardConfig.h>
2019-04-05 06:20:22 -03:00
# include <AP_Logger/AP_Logger.h>
2022-11-06 19:44:25 -04:00
# include <AP_SerialManager/AP_SerialManager.h>
2019-07-09 03:14:52 -03:00
# include <AP_Vehicle/AP_Vehicle_Type.h>
2019-04-05 06:20:22 -03:00
2016-04-14 13:42:06 -03:00
extern const AP_HAL : : HAL & hal ;
2016-04-14 17:00:38 -03:00
2014-06-26 23:56:50 -03:00
// table of user settable parameters
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo RangeFinder : : var_info [ ] = {
2018-07-04 11:22:17 -03:00
// @Group: 1_
// @Path: AP_RangeFinder_Params.cpp
2019-06-10 23:47:56 -03:00
AP_SUBGROUPINFO ( params [ 0 ] , " 1_ " , 25 , RangeFinder , AP_RangeFinder_Params ) ,
2018-07-04 11:22:17 -03:00
// @Group: 1_
2023-02-27 16:20:51 -04:00
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp
2018-07-04 11:22:17 -03:00
AP_SUBGROUPVARPTR ( drivers [ 0 ] , " 1_ " , 57 , RangeFinder , backend_var_info [ 0 ] ) ,
2018-05-16 19:31:22 -03:00
2016-10-16 19:15:06 -03:00
# if RANGEFINDER_MAX_INSTANCES > 1
2018-07-04 11:22:17 -03:00
// @Group: 2_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO ( params [ 1 ] , " 2_ " , 27 , RangeFinder , AP_RangeFinder_Params ) ,
2018-05-16 19:31:22 -03:00
2018-05-24 23:00:02 -03:00
// @Group: 2_
2023-02-27 16:20:51 -04:00
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp
2018-07-04 11:22:17 -03:00
AP_SUBGROUPVARPTR ( drivers [ 1 ] , " 2_ " , 58 , RangeFinder , backend_var_info [ 1 ] ) ,
2015-08-28 06:52:34 -03:00
# endif
2015-09-10 07:27:12 -03:00
# if RANGEFINDER_MAX_INSTANCES > 2
2018-07-04 11:22:17 -03:00
// @Group: 3_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO ( params [ 2 ] , " 3_ " , 29 , RangeFinder , AP_RangeFinder_Params ) ,
2018-05-16 19:31:22 -03:00
2018-05-24 23:00:02 -03:00
// @Group: 3_
2023-02-27 16:20:51 -04:00
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp
2018-07-04 11:22:17 -03:00
AP_SUBGROUPVARPTR ( drivers [ 2 ] , " 3_ " , 59 , RangeFinder , backend_var_info [ 2 ] ) ,
2016-07-26 02:47:25 -03:00
# endif
# if RANGEFINDER_MAX_INSTANCES > 3
2018-07-04 11:22:17 -03:00
// @Group: 4_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO ( params [ 3 ] , " 4_ " , 31 , RangeFinder , AP_RangeFinder_Params ) ,
2018-05-16 19:31:22 -03:00
2018-05-24 23:00:02 -03:00
// @Group: 4_
2023-02-27 16:20:51 -04:00
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp
2020-01-14 19:50:09 -04:00
AP_SUBGROUPVARPTR ( drivers [ 3 ] , " 4_ " , 60 , RangeFinder , backend_var_info [ 3 ] ) ,
2018-07-04 11:22:17 -03:00
# endif
# if RANGEFINDER_MAX_INSTANCES > 4
// @Group: 5_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO ( params [ 4 ] , " 5_ " , 33 , RangeFinder , AP_RangeFinder_Params ) ,
// @Group: 5_
2023-02-27 16:20:51 -04:00
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp
2018-07-04 11:22:17 -03:00
AP_SUBGROUPVARPTR ( drivers [ 4 ] , " 5_ " , 34 , RangeFinder , backend_var_info [ 4 ] ) ,
# endif
# if RANGEFINDER_MAX_INSTANCES > 5
// @Group: 6_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO ( params [ 5 ] , " 6_ " , 35 , RangeFinder , AP_RangeFinder_Params ) ,
// @Group: 6_
2023-02-27 16:20:51 -04:00
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp
2018-07-04 11:22:17 -03:00
AP_SUBGROUPVARPTR ( drivers [ 5 ] , " 6_ " , 36 , RangeFinder , backend_var_info [ 5 ] ) ,
# endif
# if RANGEFINDER_MAX_INSTANCES > 6
// @Group: 7_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO ( params [ 6 ] , " 7_ " , 37 , RangeFinder , AP_RangeFinder_Params ) ,
// @Group: 7_
2023-02-27 16:20:51 -04:00
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp
2018-07-04 11:22:17 -03:00
AP_SUBGROUPVARPTR ( drivers [ 6 ] , " 7_ " , 38 , RangeFinder , backend_var_info [ 6 ] ) ,
# endif
# if RANGEFINDER_MAX_INSTANCES > 7
// @Group: 8_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO ( params [ 7 ] , " 8_ " , 39 , RangeFinder , AP_RangeFinder_Params ) ,
// @Group: 8_
2023-02-27 16:20:51 -04:00
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp
2018-07-04 11:22:17 -03:00
AP_SUBGROUPVARPTR ( drivers [ 7 ] , " 8_ " , 40 , RangeFinder , backend_var_info [ 7 ] ) ,
2015-09-10 07:27:12 -03:00
# endif
2018-05-16 19:31:22 -03:00
2018-07-04 11:22:17 -03:00
# if RANGEFINDER_MAX_INSTANCES > 8
// @Group: 9_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO ( params [ 8 ] , " 9_ " , 41 , RangeFinder , AP_RangeFinder_Params ) ,
// @Group: 9_
2023-02-27 16:20:51 -04:00
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp
2018-07-04 11:22:17 -03:00
AP_SUBGROUPVARPTR ( drivers [ 8 ] , " 9_ " , 42 , RangeFinder , backend_var_info [ 8 ] ) ,
# endif
# if RANGEFINDER_MAX_INSTANCES > 9
// @Group: A_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO ( params [ 9 ] , " A_ " , 43 , RangeFinder , AP_RangeFinder_Params ) ,
// @Group: A_
2023-02-27 16:20:51 -04:00
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp
2018-07-04 11:22:17 -03:00
AP_SUBGROUPVARPTR ( drivers [ 9 ] , " A_ " , 44 , RangeFinder , backend_var_info [ 9 ] ) ,
# endif
2023-02-15 03:12:26 -04:00
2014-06-26 23:56:50 -03:00
AP_GROUPEND
} ;
2018-05-16 20:05:50 -03:00
const AP_Param : : GroupInfo * RangeFinder : : backend_var_info [ RANGEFINDER_MAX_INSTANCES ] ;
2019-07-09 03:14:52 -03:00
RangeFinder : : RangeFinder ( )
2015-06-08 00:10:43 -03:00
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
2018-05-09 04:45:26 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if ( _singleton ! = nullptr ) {
AP_HAL : : panic ( " Rangefinder must be singleton " ) ;
}
# endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
_singleton = this ;
2015-06-08 00:10:43 -03:00
}
2014-06-26 23:56:50 -03:00
/*
initialise the RangeFinder class . We do detection of attached range
finders here . For now we won ' t allow for hot - plugging of
rangefinders .
*/
2019-04-05 06:13:42 -03:00
void RangeFinder : : init ( enum Rotation orientation_default )
2014-06-26 23:56:50 -03:00
{
2023-03-05 17:58:23 -04:00
if ( num_instances ! = 0 ) {
// don't re-init if we've found some sensors already
2014-06-26 23:56:50 -03:00
return ;
}
2018-07-04 11:22:17 -03:00
2019-04-05 06:13:42 -03:00
// set orientation defaults
for ( uint8_t i = 0 ; i < RANGEFINDER_MAX_INSTANCES ; i + + ) {
params [ i ] . orientation . set_default ( orientation_default ) ;
}
2018-02-23 08:11:47 -04:00
for ( uint8_t i = 0 , serial_instance = 0 ; i < RANGEFINDER_MAX_INSTANCES ; i + + ) {
// serial_instance will be increased inside detect_instance
// if a serial driver is loaded for this instance
2020-04-30 19:09:27 -03:00
WITH_SEMAPHORE ( detect_sem ) ;
2018-02-23 08:11:47 -04:00
detect_instance ( i , serial_instance ) ;
2016-10-30 02:24:21 -03:00
if ( drivers [ i ] ! = nullptr ) {
2014-06-26 23:56:50 -03:00
// we loaded a driver for this instance, so it must be
2020-04-30 19:09:27 -03:00
// present (although it may not be healthy). We use MAX()
// here as a UAVCAN rangefinder may already have been
// found
num_instances = MAX ( num_instances , i + 1 ) ;
2014-06-26 23:56:50 -03:00
}
2015-04-13 03:03:19 -03:00
// initialise status
2019-11-01 02:10:52 -03:00
state [ i ] . status = Status : : NotConnected ;
2015-04-13 03:03:19 -03:00
state [ i ] . range_valid_count = 0 ;
2014-06-05 11:31:15 -03:00
}
2014-06-26 23:56:50 -03:00
}
/*
update RangeFinder state for all instances . This should be called at
around 10 Hz by main loop
*/
void RangeFinder : : update ( void )
{
for ( uint8_t i = 0 ; i < num_instances ; i + + ) {
2016-10-30 02:24:21 -03:00
if ( drivers [ i ] ! = nullptr ) {
2019-11-01 00:03:14 -03:00
if ( ( Type ) params [ i ] . type . get ( ) = = Type : : NONE ) {
2014-06-26 23:56:50 -03:00
// allow user to disable a rangefinder at runtime
2019-11-01 02:10:52 -03:00
state [ i ] . status = Status : : NotConnected ;
2015-04-13 03:03:19 -03:00
state [ i ] . range_valid_count = 0 ;
2014-06-26 23:56:50 -03:00
continue ;
}
drivers [ i ] - > update ( ) ;
}
}
2021-11-23 01:53:24 -04:00
# if HAL_LOGGING_ENABLED
2019-04-05 06:20:22 -03:00
Log_RFND ( ) ;
2019-10-19 01:28:27 -03:00
# endif
2014-06-26 23:56:50 -03:00
}
2016-04-14 16:59:31 -03:00
2021-06-04 18:36:24 -03:00
bool RangeFinder : : _add_backend ( AP_RangeFinder_Backend * backend , uint8_t instance , uint8_t serial_instance )
2016-04-14 16:59:31 -03:00
{
if ( ! backend ) {
2016-11-11 17:58:46 -04:00
return false ;
2016-04-14 16:59:31 -03:00
}
2020-11-26 17:51:38 -04:00
if ( instance > = RANGEFINDER_MAX_INSTANCES ) {
2016-04-14 16:59:31 -03:00
AP_HAL : : panic ( " Too many RANGERS backends " ) ;
}
2020-11-26 17:51:38 -04:00
if ( drivers [ instance ] ! = nullptr ) {
// we've allocated the same instance twice
INTERNAL_ERROR ( AP_InternalError : : error_t : : flow_of_control ) ;
}
2021-06-04 18:36:24 -03:00
backend - > init_serial ( serial_instance ) ;
2020-11-26 17:51:38 -04:00
drivers [ instance ] = backend ;
num_instances = MAX ( num_instances , instance + 1 ) ;
2016-04-14 16:59:31 -03:00
2016-11-11 17:58:46 -04:00
return true ;
2016-04-14 16:59:31 -03:00
}
2016-11-10 22:18:45 -04:00
2014-06-26 23:56:50 -03:00
/*
detect if an instance of a rangefinder is connected .
*/
2018-02-23 08:11:47 -04:00
void RangeFinder : : detect_instance ( uint8_t instance , uint8_t & serial_instance )
2014-06-26 23:56:50 -03:00
{
2022-03-08 00:04:15 -04:00
# if AP_RANGEFINDER_ENABLED
2022-06-22 08:03:22 -03:00
AP_RangeFinder_Backend_Serial * ( * serial_create_fn ) ( RangeFinder : : RangeFinder_State & , AP_RangeFinder_Params & ) = nullptr ;
2019-11-01 00:03:24 -03:00
const Type _type = ( Type ) params [ instance ] . type . get ( ) ;
2017-08-07 00:04:56 -03:00
switch ( _type ) {
2019-11-01 00:03:14 -03:00
case Type : : PLI2C :
case Type : : PLI2CV3 :
case Type : : PLI2CV3HP :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED
2019-02-11 05:48:05 -04:00
FOREACH_I2C ( i ) {
2020-11-26 17:51:38 -04:00
if ( _add_backend ( AP_RangeFinder_PulsedLightLRF : : detect ( i , state [ instance ] , params [ instance ] , _type ) ,
instance ) ) {
2019-02-11 05:48:05 -04:00
break ;
}
2016-11-11 17:58:46 -04:00
}
2022-03-12 06:37:29 -04:00
# endif
2016-12-03 07:02:03 -04:00
break ;
2020-06-18 22:25:39 -03:00
case Type : : MBI2C : {
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED
2020-06-18 22:25:39 -03:00
uint8_t addr = AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR ;
if ( params [ instance ] . address ! = 0 ) {
addr = params [ instance ] . address ;
}
2019-02-11 05:48:05 -04:00
FOREACH_I2C ( i ) {
if ( _add_backend ( AP_RangeFinder_MaxsonarI2CXL : : detect ( state [ instance ] , params [ instance ] ,
2020-06-18 22:25:39 -03:00
hal . i2c_mgr - > get_device ( i , addr ) ) ,
2020-11-26 17:51:38 -04:00
instance ) ) {
2019-02-11 05:48:05 -04:00
break ;
}
2017-09-23 19:33:04 -03:00
}
2016-12-03 07:02:03 -04:00
break ;
2022-03-12 06:37:29 -04:00
# endif
2020-06-18 22:25:39 -03:00
}
2019-11-01 00:03:14 -03:00
case Type : : LWI2C :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_LWI2C_ENABLED
2018-07-04 11:22:17 -03:00
if ( params [ instance ] . address ) {
2019-07-19 03:56:40 -03:00
// the LW20 needs a long time to boot up, so we delay 1.5s here
2023-03-05 17:58:23 -04:00
# ifndef HAL_BUILD_AP_PERIPH
2019-07-19 03:56:40 -03:00
if ( ! hal . util - > was_watchdog_armed ( ) ) {
hal . scheduler - > delay ( 1500 ) ;
}
2023-03-05 17:58:23 -04:00
# endif
2017-09-23 16:25:32 -03:00
# ifdef HAL_RANGEFINDER_LIGHTWARE_I2C_BUS
2018-07-04 11:22:17 -03:00
_add_backend ( AP_RangeFinder_LightWareI2C : : detect ( state [ instance ] , params [ instance ] ,
2020-11-26 17:51:38 -04:00
hal . i2c_mgr - > get_device ( HAL_RANGEFINDER_LIGHTWARE_I2C_BUS , params [ instance ] . address ) ) ,
instance ) ;
2017-09-23 16:25:32 -03:00
# else
2019-02-11 05:48:05 -04:00
FOREACH_I2C ( i ) {
if ( _add_backend ( AP_RangeFinder_LightWareI2C : : detect ( state [ instance ] , params [ instance ] ,
2020-11-26 17:51:38 -04:00
hal . i2c_mgr - > get_device ( i , params [ instance ] . address ) ) ,
instance ) ) {
2019-02-11 05:48:05 -04:00
break ;
}
2017-09-23 16:25:32 -03:00
}
# endif
2015-08-28 06:52:34 -03:00
}
2022-03-12 06:37:29 -04:00
# endif // AP_RANGEFINDER_LWI2C_ENABLED
2016-12-03 07:02:03 -04:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : TRI2C :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_TRI2C_ENABLED
2018-07-04 11:22:17 -03:00
if ( params [ instance ] . address ) {
2019-02-11 05:48:05 -04:00
FOREACH_I2C ( i ) {
if ( _add_backend ( AP_RangeFinder_TeraRangerI2C : : detect ( state [ instance ] , params [ instance ] ,
2020-11-26 17:51:38 -04:00
hal . i2c_mgr - > get_device ( i , params [ instance ] . address ) ) ,
instance ) ) {
2019-02-11 05:48:05 -04:00
break ;
}
2017-07-28 09:20:10 -03:00
}
2016-12-15 20:53:30 -04:00
}
2022-03-12 06:37:29 -04:00
# endif
2016-12-15 20:53:30 -04:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : VL53L0X :
2019-12-10 23:10:02 -04:00
case Type : : VL53L1X_Short :
2019-02-11 05:48:05 -04:00
FOREACH_I2C ( i ) {
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_VL53L0X_ENABLED
2019-02-11 05:48:05 -04:00
if ( _add_backend ( AP_RangeFinder_VL53L0X : : detect ( state [ instance ] , params [ instance ] ,
2020-11-26 17:51:38 -04:00
hal . i2c_mgr - > get_device ( i , params [ instance ] . address ) ) ,
instance ) ) {
2019-02-11 05:48:05 -04:00
break ;
}
2022-03-12 06:37:29 -04:00
# endif
# if AP_RANGEFINDER_VL53L1X_ENABLED
2019-02-11 05:48:05 -04:00
if ( _add_backend ( AP_RangeFinder_VL53L1X : : detect ( state [ instance ] , params [ instance ] ,
2019-12-10 23:10:02 -04:00
hal . i2c_mgr - > get_device ( i , params [ instance ] . address ) ,
_type = = Type : : VL53L1X_Short ? AP_RangeFinder_VL53L1X : : DistanceMode : : Short :
2020-11-26 17:51:38 -04:00
AP_RangeFinder_VL53L1X : : DistanceMode : : Long ) ,
instance ) ) {
2019-02-11 05:48:05 -04:00
break ;
2018-11-17 07:17:51 -04:00
}
2022-03-12 06:37:29 -04:00
# endif
2018-11-17 07:17:51 -04:00
}
2017-03-09 19:38:28 -04:00
break ;
2021-10-23 04:52:21 -03:00
case Type : : BenewakeTFminiPlus : {
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED
2022-03-12 18:19:38 -04:00
uint8_t addr = TFMINIPLUS_ADDR_DEFAULT ;
2021-10-23 04:52:21 -03:00
if ( params [ instance ] . address ! = 0 ) {
addr = params [ instance ] . address ;
}
2019-04-26 04:23:45 -03:00
FOREACH_I2C ( i ) {
if ( _add_backend ( AP_RangeFinder_Benewake_TFMiniPlus : : detect ( state [ instance ] , params [ instance ] ,
2021-10-23 04:52:21 -03:00
hal . i2c_mgr - > get_device ( i , addr ) ) ,
2020-11-26 17:51:38 -04:00
instance ) ) {
2019-04-26 04:23:45 -03:00
break ;
}
}
break ;
2022-03-12 06:37:29 -04:00
# endif
2021-10-23 04:52:21 -03:00
}
2019-11-01 00:03:14 -03:00
case Type : : PX4_PWM :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_PWM_ENABLED
2018-11-06 01:17:19 -04:00
// to ease moving from PX4 to ChibiOS we'll lie a little about
// the backend driver...
if ( AP_RangeFinder_PWM : : detect ( ) ) {
2020-11-26 17:51:38 -04:00
_add_backend ( new AP_RangeFinder_PWM ( state [ instance ] , params [ instance ] , estimated_terrain_height ) , instance ) ;
2018-11-06 01:17:19 -04:00
}
2015-07-06 16:24:06 -03:00
# endif
2020-09-06 22:39:45 -03:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : BBB_PRU :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_BBB_PRU_ENABLED
2017-08-07 00:41:01 -03:00
if ( AP_RangeFinder_BBB_PRU : : detect ( ) ) {
2020-11-26 17:51:38 -04:00
_add_backend ( new AP_RangeFinder_BBB_PRU ( state [ instance ] , params [ instance ] ) , instance ) ;
2015-07-06 16:24:06 -03:00
}
2014-06-27 02:02:51 -03:00
# endif
2020-09-06 22:39:45 -03:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : LWSER :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_LightWareSerial : : create ;
2022-03-12 06:37:29 -04:00
# endif
2016-12-03 07:02:03 -04:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : LEDDARONE :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_LEDDARONE_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_LeddarOne : : create ;
2022-03-12 06:37:29 -04:00
# endif
2016-12-03 07:02:03 -04:00
break ;
2021-10-18 00:47:20 -03:00
case Type : : USD1_Serial :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_USD1_SERIAL_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_USD1_Serial : : create ;
2022-03-12 06:37:29 -04:00
# endif
2016-12-03 07:02:03 -04:00
break ;
2020-09-06 22:39:45 -03:00
case Type : : BEBOP :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_BEBOP_ENABLED
2017-08-07 00:41:01 -03:00
if ( AP_RangeFinder_Bebop : : detect ( ) ) {
2020-11-26 17:51:38 -04:00
_add_backend ( new AP_RangeFinder_Bebop ( state [ instance ] , params [ instance ] ) , instance ) ;
2016-04-15 14:31:51 -03:00
}
# endif
2020-09-06 22:39:45 -03:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : MAVLink :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_MAVLINK_ENABLED
2017-08-07 00:41:01 -03:00
if ( AP_RangeFinder_MAVLink : : detect ( ) ) {
2020-11-26 17:51:38 -04:00
_add_backend ( new AP_RangeFinder_MAVLink ( state [ instance ] , params [ instance ] ) , instance ) ;
2016-05-04 00:02:44 -03:00
}
2019-10-24 08:35:19 -03:00
# endif
2016-12-03 07:02:03 -04:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : MBSER :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_MaxsonarSerialLV : : create ;
2022-03-12 06:37:29 -04:00
# endif
2016-12-03 07:02:03 -04:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : ANALOG :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_ANALOG_ENABLED
2016-12-03 13:44:06 -04:00
// note that analog will always come back as present if the pin is valid
2018-07-04 11:22:17 -03:00
if ( AP_RangeFinder_analog : : detect ( params [ instance ] ) ) {
2020-11-26 17:51:38 -04:00
_add_backend ( new AP_RangeFinder_analog ( state [ instance ] , params [ instance ] ) , instance ) ;
2014-06-26 23:56:50 -03:00
}
2020-05-17 03:41:50 -03:00
# endif
break ;
case Type : : HC_SR04 :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_HC_SR04_ENABLED
2020-05-17 03:41:50 -03:00
// note that this will always come back as present if the pin is valid
if ( AP_RangeFinder_HC_SR04 : : detect ( params [ instance ] ) ) {
2020-11-26 17:51:38 -04:00
_add_backend ( new AP_RangeFinder_HC_SR04 ( state [ instance ] , params [ instance ] ) , instance ) ;
2020-05-17 03:41:50 -03:00
}
2019-10-24 08:35:19 -03:00
# endif
2016-12-03 07:02:03 -04:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : NMEA :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_NMEA_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_NMEA : : create ;
2022-03-12 06:37:29 -04:00
# endif
2018-05-28 17:11:53 -03:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : WASP :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_WASP_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_Wasp : : create ;
2022-03-12 06:37:29 -04:00
# endif
2018-05-14 02:03:08 -03:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : BenewakeTF02 :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_BENEWAKE_TF02_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_Benewake_TF02 : : create ;
2022-03-12 06:37:29 -04:00
# endif
2018-05-25 22:59:36 -03:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : BenewakeTFmini :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_Benewake_TFMini : : create ;
2022-03-12 06:37:29 -04:00
# endif
2018-05-25 22:59:36 -03:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : BenewakeTF03 :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_BENEWAKE_TF03_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_Benewake_TF03 : : create ;
2022-08-01 20:44:01 -03:00
# endif
break ;
case Type : : TeraRanger_Serial :
# if AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED
serial_create_fn = AP_RangeFinder_TeraRanger_Serial : : create ;
2022-03-12 06:37:29 -04:00
# endif
2019-10-14 06:30:48 -03:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : PWM :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_PWM_ENABLED
2018-08-29 11:18:49 -03:00
if ( AP_RangeFinder_PWM : : detect ( ) ) {
2020-11-26 17:51:38 -04:00
_add_backend ( new AP_RangeFinder_PWM ( state [ instance ] , params [ instance ] , estimated_terrain_height ) , instance ) ;
2018-08-29 11:18:49 -03:00
}
2019-10-24 08:35:19 -03:00
# endif
2018-08-29 11:18:49 -03:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : BLPing :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_BLPING_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_BLPing : : create ;
2022-03-12 06:37:29 -04:00
# endif
2019-03-28 09:43:23 -03:00
break ;
2019-11-01 00:03:14 -03:00
case Type : : Lanbao :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_LANBAO_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_Lanbao : : create ;
2022-03-12 06:37:29 -04:00
# endif
2019-08-31 08:21:01 -03:00
break ;
2020-01-13 01:48:57 -04:00
case Type : : LeddarVu8_Serial :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_LEDDARVU8_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_LeddarVu8 : : create ;
2022-03-12 06:37:29 -04:00
# endif
2020-01-13 01:48:57 -04:00
break ;
2020-04-30 19:09:27 -03:00
case Type : : UAVCAN :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_UAVCAN_ENABLED
2020-04-30 19:09:27 -03:00
/*
the UAVCAN driver gets created when we first receive a
measurement . We take the instance slot now , even if we don ' t
yet have the driver
*/
num_instances = MAX ( num_instances , instance + 1 ) ;
# endif
2020-09-06 22:39:45 -03:00
break ;
2020-04-30 19:09:27 -03:00
2020-06-14 03:11:25 -03:00
case Type : : GYUS42v2 :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_GYUS42V2_ENABLED
2022-06-22 08:03:22 -03:00
serial_create_fn = AP_RangeFinder_GYUS42v2 : : create ;
2022-03-12 06:37:29 -04:00
# endif
2020-06-14 03:11:25 -03:00
break ;
2021-07-30 07:41:47 -03:00
case Type : : SIM :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_SIM_ENABLED
2020-11-26 17:51:38 -04:00
_add_backend ( new AP_RangeFinder_SITL ( state [ instance ] , params [ instance ] , instance ) , instance ) ;
2020-07-17 20:36:47 -03:00
# endif
2020-09-06 22:39:45 -03:00
break ;
2020-07-17 20:36:47 -03:00
2020-08-04 17:42:19 -03:00
case Type : : MSP :
2020-09-06 22:39:45 -03:00
# if HAL_MSP_RANGEFINDER_ENABLED
2020-08-04 17:42:19 -03:00
if ( AP_RangeFinder_MSP : : detect ( ) ) {
2020-11-26 17:51:38 -04:00
_add_backend ( new AP_RangeFinder_MSP ( state [ instance ] , params [ instance ] ) , instance ) ;
2020-08-04 17:42:19 -03:00
}
2020-08-31 06:16:32 -03:00
# endif // HAL_MSP_RANGEFINDER_ENABLED
2020-09-06 22:39:45 -03:00
break ;
2020-08-04 17:42:19 -03:00
2020-12-31 20:10:39 -04:00
case Type : : USD1_CAN :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_USD1_CAN_ENABLED
2020-12-31 20:10:39 -04:00
_add_backend ( new AP_RangeFinder_USD1_CAN ( state [ instance ] , params [ instance ] ) , instance ) ;
2022-03-12 06:37:29 -04:00
# endif
2020-12-31 20:10:39 -04:00
break ;
2021-11-12 06:11:48 -04:00
case Type : : Benewake_CAN :
2022-03-12 06:37:29 -04:00
# if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED
2021-11-12 06:11:48 -04:00
_add_backend ( new AP_RangeFinder_Benewake_CAN ( state [ instance ] , params [ instance ] ) , instance ) ;
2023-02-15 03:12:26 -04:00
# endif
2021-11-12 06:11:48 -04:00
break ;
2023-02-15 03:12:26 -04:00
case Type : : Lua_Scripting :
# if AP_SCRIPTING_ENABLED
_add_backend ( new AP_RangeFinder_Lua ( state [ instance ] , params [ instance ] ) , instance ) ;
2022-03-12 06:37:29 -04:00
# endif
2023-02-15 03:12:26 -04:00
break ;
2020-09-06 22:39:45 -03:00
case Type : : NONE :
2016-12-03 07:02:03 -04:00
break ;
2014-06-05 11:31:15 -03:00
}
2018-05-16 20:05:50 -03:00
2022-06-22 08:03:22 -03:00
if ( serial_create_fn ! = nullptr ) {
if ( AP : : serialmanager ( ) . have_serial ( AP_SerialManager : : SerialProtocol_Rangefinder , serial_instance ) ) {
auto * b = serial_create_fn ( state [ instance ] , params [ instance ] ) ;
if ( b ! = nullptr ) {
_add_backend ( b , instance , serial_instance + + ) ;
}
}
}
2018-05-16 20:05:50 -03:00
// if the backend has some local parameters then make those available in the tree
if ( drivers [ instance ] & & state [ instance ] . var_info ) {
backend_var_info [ instance ] = state [ instance ] . var_info ;
AP_Param : : load_object_from_eeprom ( drivers [ instance ] , backend_var_info [ instance ] ) ;
2020-04-18 20:01:25 -03:00
// param count could have changed
AP_Param : : invalidate_count ( ) ;
2018-05-16 20:05:50 -03:00
}
2022-03-08 00:04:15 -04:00
# endif //AP_RANGEFINDER_ENABLED
2012-01-10 19:44:04 -04:00
}
2017-08-08 02:54:09 -03:00
AP_RangeFinder_Backend * RangeFinder : : get_backend ( uint8_t id ) const {
if ( id > = num_instances ) {
return nullptr ;
2015-04-13 03:03:19 -03:00
}
2017-08-08 02:54:09 -03:00
if ( drivers [ id ] ! = nullptr ) {
2019-11-01 00:03:14 -03:00
if ( drivers [ id ] - > type ( ) = = Type : : NONE ) {
2017-08-08 02:54:09 -03:00
// pretend it isn't here; disabled at runtime?
return nullptr ;
}
2015-04-13 03:03:19 -03:00
}
2017-08-08 02:54:09 -03:00
return drivers [ id ] ;
} ;
2015-04-13 03:03:19 -03:00
2019-11-01 02:10:52 -03:00
RangeFinder : : Status RangeFinder : : status_orient ( enum Rotation orientation ) const
2017-02-09 06:26:57 -04:00
{
2017-08-08 02:54:09 -03:00
AP_RangeFinder_Backend * backend = find_instance ( orientation ) ;
if ( backend = = nullptr ) {
2019-11-01 02:10:52 -03:00
return Status : : NotConnected ;
2017-02-09 06:26:57 -04:00
}
2017-08-08 02:54:09 -03:00
return backend - > status ( ) ;
2017-02-09 06:26:57 -04:00
}
2019-04-30 07:22:49 -03:00
void RangeFinder : : handle_msg ( const mavlink_message_t & msg )
2017-02-09 06:26:57 -04:00
{
uint8_t i ;
for ( i = 0 ; i < num_instances ; i + + ) {
2019-11-01 00:03:14 -03:00
if ( ( drivers [ i ] ! = nullptr ) & & ( ( Type ) params [ i ] . type . get ( ) ! = Type : : NONE ) ) {
2016-05-03 23:59:01 -03:00
drivers [ i ] - > handle_msg ( msg ) ;
2017-02-09 06:26:57 -04:00
}
}
}
2020-08-31 06:16:32 -03:00
# if HAL_MSP_RANGEFINDER_ENABLED
2020-09-07 19:29:23 -03:00
void RangeFinder : : handle_msp ( const MSP : : msp_rangefinder_data_message_t & pkt )
2020-08-04 17:42:19 -03:00
{
uint8_t i ;
for ( i = 0 ; i < num_instances ; i + + ) {
if ( ( drivers [ i ] ! = nullptr ) & & ( ( Type ) params [ i ] . type . get ( ) = = Type : : MSP ) ) {
drivers [ i ] - > handle_msp ( pkt ) ;
}
}
}
2020-08-31 06:16:32 -03:00
# endif // HAL_MSP_RANGEFINDER_ENABLED
2020-08-04 17:42:19 -03:00
2017-02-09 06:26:57 -04:00
// return true if we have a range finder with the specified orientation
bool RangeFinder : : has_orientation ( enum Rotation orientation ) const
{
2017-08-08 02:54:09 -03:00
return ( find_instance ( orientation ) ! = nullptr ) ;
2017-02-09 06:26:57 -04:00
}
// find first range finder instance with the specified orientation
2017-08-08 02:54:09 -03:00
AP_RangeFinder_Backend * RangeFinder : : find_instance ( enum Rotation orientation ) const
2017-02-09 06:26:57 -04:00
{
2019-10-23 19:03:55 -03:00
// first try for a rangefinder that is in range
2017-02-09 06:26:57 -04:00
for ( uint8_t i = 0 ; i < num_instances ; i + + ) {
2017-08-08 02:54:09 -03:00
AP_RangeFinder_Backend * backend = get_backend ( i ) ;
2019-10-23 19:03:55 -03:00
if ( backend ! = nullptr & &
backend - > orientation ( ) = = orientation & &
2019-11-01 02:10:52 -03:00
backend - > status ( ) = = Status : : Good ) {
2019-10-23 19:03:55 -03:00
return backend ;
2017-02-09 06:26:57 -04:00
}
2019-10-23 19:03:55 -03:00
}
// if none in range then return first with correct orientation
for ( uint8_t i = 0 ; i < num_instances ; i + + ) {
AP_RangeFinder_Backend * backend = get_backend ( i ) ;
if ( backend ! = nullptr & &
backend - > orientation ( ) = = orientation ) {
return backend ;
2017-08-08 02:54:09 -03:00
}
2017-02-09 06:26:57 -04:00
}
2017-08-08 02:54:09 -03:00
return nullptr ;
2017-02-09 06:26:57 -04:00
}
2021-10-18 02:45:33 -03:00
float RangeFinder : : distance_orient ( enum Rotation orientation ) const
{
AP_RangeFinder_Backend * backend = find_instance ( orientation ) ;
if ( backend = = nullptr ) {
return 0 ;
}
return backend - > distance ( ) ;
}
2017-02-09 06:26:57 -04:00
uint16_t RangeFinder : : distance_cm_orient ( enum Rotation orientation ) const
{
2022-04-18 02:50:50 -03:00
return distance_orient ( orientation ) * 100.0 ;
2017-02-09 06:26:57 -04:00
}
int16_t RangeFinder : : max_distance_cm_orient ( enum Rotation orientation ) const
{
2017-08-08 02:54:09 -03:00
AP_RangeFinder_Backend * backend = find_instance ( orientation ) ;
if ( backend = = nullptr ) {
return 0 ;
2017-02-09 06:26:57 -04:00
}
2017-08-08 02:54:09 -03:00
return backend - > max_distance_cm ( ) ;
2017-02-09 06:26:57 -04:00
}
int16_t RangeFinder : : min_distance_cm_orient ( enum Rotation orientation ) const
{
2017-08-08 02:54:09 -03:00
AP_RangeFinder_Backend * backend = find_instance ( orientation ) ;
if ( backend = = nullptr ) {
return 0 ;
2017-02-09 06:26:57 -04:00
}
2017-08-08 02:54:09 -03:00
return backend - > min_distance_cm ( ) ;
2017-02-09 06:26:57 -04:00
}
int16_t RangeFinder : : ground_clearance_cm_orient ( enum Rotation orientation ) const
{
2017-08-08 02:54:09 -03:00
AP_RangeFinder_Backend * backend = find_instance ( orientation ) ;
if ( backend = = nullptr ) {
return 0 ;
2015-04-13 03:03:19 -03:00
}
2017-08-08 02:54:09 -03:00
return backend - > ground_clearance_cm ( ) ;
2015-04-13 03:03:19 -03:00
}
2017-02-09 06:26:57 -04:00
bool RangeFinder : : has_data_orient ( enum Rotation orientation ) const
{
2017-08-08 02:54:09 -03:00
AP_RangeFinder_Backend * backend = find_instance ( orientation ) ;
if ( backend = = nullptr ) {
return false ;
2017-02-09 06:26:57 -04:00
}
2017-08-08 02:54:09 -03:00
return backend - > has_data ( ) ;
2017-02-09 06:26:57 -04:00
}
uint8_t RangeFinder : : range_valid_count_orient ( enum Rotation orientation ) const
{
2017-08-08 02:54:09 -03:00
AP_RangeFinder_Backend * backend = find_instance ( orientation ) ;
if ( backend = = nullptr ) {
return 0 ;
2017-02-09 06:26:57 -04:00
}
2017-08-08 02:54:09 -03:00
return backend - > range_valid_count ( ) ;
2017-02-09 06:26:57 -04:00
}
const Vector3f & RangeFinder : : get_pos_offset_orient ( enum Rotation orientation ) const
{
2017-08-08 02:54:09 -03:00
AP_RangeFinder_Backend * backend = find_instance ( orientation ) ;
if ( backend = = nullptr ) {
return pos_offset_zero ;
2017-02-09 06:26:57 -04:00
}
2017-08-08 02:54:09 -03:00
return backend - > get_pos_offset ( ) ;
2017-05-29 14:02:51 -03:00
}
AP_RangeFinder: support last_reading_ms
Benewake, LeddarOne, LightWareSerial, MAVLink, MaxsonarI2CXL, MaxsonarSerialLV, NMEA, PX4_PWM, uLanding and Wasp already stored the last read time so for these drivers, this change just moves that storage to the state structure
analog, BBB_PRU, Bebop, LightWareI2C, PulsedLightLRF, TeraRangerI2C, VL53L0X did not store the last read time so this was added
2018-08-27 04:02:51 -03:00
uint32_t RangeFinder : : last_reading_ms ( enum Rotation orientation ) const
{
AP_RangeFinder_Backend * backend = find_instance ( orientation ) ;
if ( backend = = nullptr ) {
return 0 ;
}
return backend - > last_reading_ms ( ) ;
}
2017-08-08 04:32:53 -03:00
MAV_DISTANCE_SENSOR RangeFinder : : get_mav_distance_sensor_type_orient ( enum Rotation orientation ) const
2017-05-29 14:02:51 -03:00
{
2017-08-08 02:54:09 -03:00
AP_RangeFinder_Backend * backend = find_instance ( orientation ) ;
if ( backend = = nullptr ) {
return MAV_DISTANCE_SENSOR_UNKNOWN ;
2017-05-29 14:02:51 -03:00
}
2017-08-08 04:32:53 -03:00
return backend - > get_mav_distance_sensor_type ( ) ;
2017-05-29 14:02:51 -03:00
}
2018-05-09 04:45:26 -03:00
2021-04-13 05:07:06 -03:00
// get temperature reading in C. returns true on success and populates temp argument
2021-06-04 13:32:44 -03:00
bool RangeFinder : : get_temp ( enum Rotation orientation , float & temp ) const
2021-04-13 05:07:06 -03:00
{
AP_RangeFinder_Backend * backend = find_instance ( orientation ) ;
if ( backend = = nullptr ) {
return false ;
}
return backend - > get_temp ( temp ) ;
}
2019-04-05 06:20:22 -03:00
// Write an RFND (rangefinder) packet
2021-02-01 12:26:33 -04:00
void RangeFinder : : Log_RFND ( ) const
2019-04-05 06:20:22 -03:00
{
if ( _log_rfnd_bit = = uint32_t ( - 1 ) ) {
return ;
}
AP_Logger & logger = AP : : logger ( ) ;
if ( ! logger . should_log ( _log_rfnd_bit ) ) {
return ;
}
2019-05-29 21:28:17 -03:00
for ( uint8_t i = 0 ; i < RANGEFINDER_MAX_INSTANCES ; i + + ) {
const AP_RangeFinder_Backend * s = get_backend ( i ) ;
if ( s = = nullptr ) {
continue ;
}
2019-04-05 06:20:22 -03:00
2019-05-29 21:28:17 -03:00
const struct log_RFND pkt = {
LOG_PACKET_HEADER_INIT ( LOG_RFND_MSG ) ,
time_us : AP_HAL : : micros64 ( ) ,
instance : i ,
dist : s - > distance_cm ( ) ,
status : ( uint8_t ) s - > status ( ) ,
orient : s - > orientation ( ) ,
} ;
AP : : logger ( ) . WriteBlock ( & pkt , sizeof ( pkt ) ) ;
}
2019-04-05 06:20:22 -03:00
}
2019-04-10 04:32:15 -03:00
bool RangeFinder : : prearm_healthy ( char * failure_msg , const uint8_t failure_msg_len ) const
{
for ( uint8_t i = 0 ; i < RANGEFINDER_MAX_INSTANCES ; i + + ) {
2021-11-05 14:25:51 -03:00
if ( ( Type ) params [ i ] . type . get ( ) = = Type : : NONE ) {
continue ;
}
if ( drivers [ i ] = = nullptr ) {
hal . util - > snprintf ( failure_msg , failure_msg_len , " Rangefinder %X: Not Detected " , i + 1 ) ;
return false ;
}
2022-07-19 21:36:39 -03:00
// backend-specific checks. This might end up drivers[i]->arming_checks(...).
switch ( drivers [ i ] - > allocated_type ( ) ) {
case Type : : ANALOG :
case Type : : PX4_PWM :
case Type : : PWM : {
// ensure pin is configured
if ( params [ i ] . pin = = - 1 ) {
hal . util - > snprintf ( failure_msg , failure_msg_len , " RNGFND%u_PIN not set " , unsigned ( i + 1 ) ) ;
return false ;
}
2022-12-10 13:43:20 -04:00
if ( drivers [ i ] - > allocated_type ( ) = = Type : : ANALOG ) {
// Analog backend does not use GPIO pin
break ;
}
2022-07-19 21:36:39 -03:00
// ensure that the pin we're configured to use is available
if ( ! hal . gpio - > valid_pin ( params [ i ] . pin ) ) {
uint8_t servo_ch ;
if ( hal . gpio - > pin_to_servo_channel ( params [ i ] . pin , servo_ch ) ) {
hal . util - > snprintf ( failure_msg , failure_msg_len , " RNGFND%u_PIN=%d, set SERVO%u_FUNCTION=-1 " , unsigned ( i + 1 ) , int ( params [ i ] . pin . get ( ) ) , unsigned ( servo_ch + 1 ) ) ;
} else {
hal . util - > snprintf ( failure_msg , failure_msg_len , " RNGFND%u_PIN=%d invalid " , unsigned ( i + 1 ) , int ( params [ i ] . pin . get ( ) ) ) ;
}
return false ;
}
break ;
}
default :
break ;
}
2021-11-05 14:25:51 -03:00
switch ( drivers [ i ] - > status ( ) ) {
case Status : : NoData :
hal . util - > snprintf ( failure_msg , failure_msg_len , " Rangefinder %X: No Data " , i + 1 ) ;
return false ;
case Status : : NotConnected :
hal . util - > snprintf ( failure_msg , failure_msg_len , " Rangefinder %X: Not Connected " , i + 1 ) ;
return false ;
case Status : : OutOfRangeLow :
case Status : : OutOfRangeHigh :
case Status : : Good :
break ;
2019-04-10 04:32:15 -03:00
}
}
return true ;
}
2018-05-09 04:45:26 -03:00
RangeFinder * RangeFinder : : _singleton ;
2019-04-05 06:20:22 -03:00
namespace AP {
RangeFinder * rangefinder ( )
{
return RangeFinder : : get_singleton ( ) ;
}
}
2022-03-08 00:04:15 -04:00