Skip to content

Commit

Permalink
wip
Browse files Browse the repository at this point in the history
  • Loading branch information
joshanne committed Sep 12, 2023
1 parent 86aad6f commit 8f5ba8c
Show file tree
Hide file tree
Showing 8 changed files with 90 additions and 0 deletions.
3 changes: 3 additions & 0 deletions .gitmodules
Original file line number Diff line number Diff line change
Expand Up @@ -39,3 +39,6 @@
path = modules/Micro-CDR
url = https://github.com/ardupilot/Micro-CDR.git
branch = master
[submodule "modules/drivers/broadcom/AFBR-S50"]
path = modules/drivers/broadcom/AFBR-S50
url = [email protected]:Broadcom/AFBR-S50-API.git
5 changes: 5 additions & 0 deletions libraries/AP_RangeFinder/AP_RangeFinder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@
#include "AP_RangeFinder_NoopLoop.h"
#include "AP_RangeFinder_TOFSenseP_CAN.h"
#include "AP_RangeFinder_NRA24_CAN.h"
#include "AP_RangeFinder_Broadcom_AFBR_S50.h"

#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_Logger/AP_Logger.h>
Expand Down Expand Up @@ -556,6 +557,10 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
_add_backend(new AP_RangeFinder_NRA24_CAN(state[instance], params[instance]), instance);
#endif
break;
case Type::Broadcom_AFBRS50:
if (AP_RangeFinder_Broadcom_AFBRS50::detect()) {
_add_backend(new AP_RangeFinder_Broadcom_AFBRS50(state[instance], params[instance]), instance);
}

case Type::NONE:
break;
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_RangeFinder/AP_RangeFinder.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ class RangeFinder
NoopLoop_P = 37,
TOFSenseP_CAN = 38,
NRA24_CAN = 39,
Broadcom_AFBRS50 = 40,
SIM = 100,
};

Expand Down
21 changes: 21 additions & 0 deletions libraries/AP_RangeFinder/AP_RangeFinder_Broadcom_AFBR_S50.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
#include "AP_RangeFinder_config.h"

#include "AP_RangeFinder_Broadcom_AFBR_S50.h"
#include <AP_HAL/AP_HAL.h>

// constructor
AP_RangeFinder_Broadcom_AFBRS50::AP_RangeFinder_Broadcom_AFBRS50(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
AP_RangeFinder_Backend(_state, _params)
{
_hnd = Argus_CreateHandle();
}

bool AP_RangeFinder_Broadcom_AFBRS50::detect()
{
return true;
}

void AP_RangeFinder_Broadcom_AFBRS50::update(void)
{

}
30 changes: 30 additions & 0 deletions libraries/AP_RangeFinder/AP_RangeFinder_Broadcom_AFBR_S50.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#pragma once

#include "argus.h"

#include "AP_RangeFinder_Backend.h"

class AP_RangeFinder_Broadcom_AFBRS50 : public AP_RangeFinder_Backend
{
public:

// constructor
AP_RangeFinder_Broadcom_AFBRS50(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);

// detect
static bool detect();

// update state
void update(void) override;

private:
float _distance_m; // stored data

argus_hnd_t *_hnd;
argus_mode_t _mode{ARGUS_MODE_SHORT_RANGE}; // Short-Range

protected:
MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
return MAV_DISTANCE_SENSOR_LASER;
}
};
27 changes: 27 additions & 0 deletions libraries/AP_RangeFinder/wscript
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@


from waflib.TaskGen import after_method, before_method, feature
import os
import shutil


def configure(cfg):
"""test"""


def build(bld):
RANGEFINDER_LIBS = {
'cortex-m4' : 'libafbrs50_m4_fpu.a'
}
if bld.env.CORTEX in RANGEFINDER_LIBS:
path_AFBR_S50 = 'modules/drivers/broadcom/AFBR-S50/AFBR-S50'
libname = RANGEFINDER_LIBS[bld.env.CORTEX]
# we need to copy the library on cygwin as it doesn't handle linking outside build tree
shutil.copyfile(os.path.join(bld.env.SRCROOT, path_AFBR_S50, "Lib", libname),
os.path.join(bld.env.BUILDROOT,'libraries/AP_RangeFinder/libAFBR-S50-API.a'))
bld.env.LIB += ['AFBR-S50-API']
bld.env.LIBPATH += ['libraries/AP_RangeFinder']
bld.env.INCLUDES += [os.path.join(bld.env.SRCROOT, path_AFBR_S50, "Include")]



1 change: 1 addition & 0 deletions modules/drivers/broadcom/AFBR-S50
Submodule AFBR-S50 added at 945e3a
2 changes: 2 additions & 0 deletions wscript
Original file line number Diff line number Diff line change
Expand Up @@ -538,6 +538,7 @@ def configure(cfg):
else:
cfg.end_msg('maybe')
cfg.recurse('libraries/AP_Scripting')
cfg.recurse('libraries/AP_RangeFinder')

cfg.recurse('libraries/AP_GPS')
cfg.recurse('libraries/AP_HAL_SITL')
Expand Down Expand Up @@ -791,6 +792,7 @@ def _build_recursion(bld):
dirs_to_recurse.append('Tools/AP_Periph')

dirs_to_recurse.append('libraries/AP_Scripting')
dirs_to_recurse.append('libraries/AP_RangeFinder')

if bld.env.ENABLE_ONVIF:
dirs_to_recurse.append('libraries/AP_ONVIF')
Expand Down

0 comments on commit 8f5ba8c

Please sign in to comment.