Skip to content

Commit

Permalink
Prepare sensor hub HAL functions for BNO085 driver.
Browse files Browse the repository at this point in the history
Note: RESET/IRQ/BOOTN GPIOs will need to be controlled separately.
  • Loading branch information
aentinger committed May 24, 2023
1 parent ccb1482 commit 3aa45d8
Show file tree
Hide file tree
Showing 6 changed files with 188 additions and 1 deletion.
3 changes: 3 additions & 0 deletions .gitmodules
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
[submodule "sh2"]
path = sh2
url = https://github.com/pika-spark/pika-spark-sh2
5 changes: 5 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,14 +3,19 @@ cmake_minimum_required(VERSION 3.15)
##########################################################################
project("pika-spark-bno085-driver")
##########################################################################
add_subdirectory(sh2)
##########################################################################
add_executable(${PROJECT_NAME}
main.cpp
bno085.cpp
spi.cpp
)
##########################################################################
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Werror -Wextra -Wpedantic)
endif()
##########################################################################
target_link_libraries(${PROJECT_NAME} pika-spark-sh2)
##########################################################################
target_compile_features(${PROJECT_NAME} PUBLIC cxx_std_17)
##########################################################################
132 changes: 132 additions & 0 deletions bno085.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,132 @@
/**
* This software is distributed under the terms of the MIT License.
* Copyright (c) 2023 LXRobotics.
* Author: Alexander Entinger <alexander.entinger@lxrobotics.com>
* Contributors: https://github.com/107-systems/pika-spark-bno085-driver/graphs/contributors.
*/

/**************************************************************************************
* INCLUDE
**************************************************************************************/

#include "bno085.h"

#include <cstring>

/**************************************************************************************
* PRIVATE FUNCTION DECLARATIONS
**************************************************************************************/

static int priv_sh2_hal_open (sh2_Hal_t * self);
static void priv_sh2_hal_close (sh2_Hal_t * self);
static int priv_sh2_hal_read (sh2_Hal_t * self, uint8_t * pBuffer, unsigned len, uint32_t * t_us);
static int priv_sh2_hal_write (sh2_Hal_t * self, uint8_t * pBuffer, unsigned len);
static uint32_t priv_sh2_hal_getTimeUs(sh2_Hal_t * self);

/**************************************************************************************
* CTOR/DTOR
**************************************************************************************/

BNO085::BNO085(std::shared_ptr<SPI> const spi)
: _spi{spi}
, _start{std::chrono::steady_clock::now()}
{
_sh2_hal.user_reference = reinterpret_cast<void *>(this);

reset();
init();
}

/**************************************************************************************
* PUBLIC MEMBER FUNCTIONS
**************************************************************************************/

int BNO085::sh2_hal_read(uint8_t * pBuffer, unsigned len, uint32_t * /* t_us */)
{
/* Read the sensor hub header. */
uint8_t sh_hdr_rx_buf[4] = {0};
uint8_t const sh_hdr_tx_buf[4] = {0};

if (!_spi->transfer(sh_hdr_tx_buf, sh_hdr_rx_buf, sizeof(sh_hdr_tx_buf)))
return 0;

/* Determine packet size (mask out continuous bit). */
uint16_t const packet_size =
(static_cast<uint16_t>(sh_hdr_rx_buf[0]) | static_cast<uint16_t>(sh_hdr_rx_buf[1]) << 8) & 0x7FFF;

size_t const bytes_to_read = std::min(static_cast<size_t>(packet_size), static_cast<size_t>(len));

/* Ensure that we only transmit zero's. */
memset(pBuffer, 0, bytes_to_read);

/* Transmit zero's and read from the device. */
if (!_spi->transfer(pBuffer, pBuffer, bytes_to_read))
return 0;

return bytes_to_read;
}

int BNO085::sh2_hal_write(uint8_t * pBuffer, unsigned len)
{
if (!_spi->transfer(pBuffer, pBuffer, len))
return 0;

return len;
}

uint32_t BNO085::sh2_hal_getTimeUs()
{
auto const now = std::chrono::steady_clock::now();
auto const uptime = (now - _start);
return std::chrono::duration_cast<std::chrono::microseconds>(uptime).count();
}

/**************************************************************************************
* PRIVATE MEMBER FUNCTIONS
**************************************************************************************/

void BNO085::reset()
{
/* TODO. */
}

void BNO085::init()
{
_sh2_hal.open = priv_sh2_hal_open;
_sh2_hal.close = priv_sh2_hal_close;
_sh2_hal.read = priv_sh2_hal_read;
_sh2_hal.write = priv_sh2_hal_write;
_sh2_hal.getTimeUs = priv_sh2_hal_getTimeUs;
}

/**************************************************************************************
* PRIVATE FUNCTION DEFINITIONS
**************************************************************************************/

int priv_sh2_hal_open(sh2_Hal_t * /* self */)
{
return 0;
}

void priv_sh2_hal_close(sh2_Hal_t * /* self */)
{
/* Do nothing. */
}

int priv_sh2_hal_read(sh2_Hal_t * self, uint8_t * pBuffer, unsigned len, uint32_t * t_us)
{
BNO085 * this_ptr = reinterpret_cast<BNO085 *>(self->user_reference);
return this_ptr->sh2_hal_read(pBuffer, len, t_us);
}

int priv_sh2_hal_write(sh2_Hal_t * self, uint8_t * pBuffer, unsigned len)
{
BNO085 * this_ptr = reinterpret_cast<BNO085 *>(self->user_reference);
return this_ptr->sh2_hal_write(pBuffer, len);
}

uint32_t priv_sh2_hal_getTimeUs(sh2_Hal_t * self)
{
BNO085 * this_ptr = reinterpret_cast<BNO085 *>(self->user_reference);
return this_ptr->sh2_hal_getTimeUs();
}
44 changes: 44 additions & 0 deletions bno085.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
/**
* This software is distributed under the terms of the MIT License.
* Copyright (c) 2023 LXRobotics.
* Author: Alexander Entinger <alexander.entinger@lxrobotics.com>
* Contributors: https://github.com/107-systems/pika-spark-bno085-driver/graphs/contributors.
*/

#pragma once

/**************************************************************************************
* INCLUDE
**************************************************************************************/

#include <chrono>
#include <memory>

#include <sh2.h>

#include "spi.h"

/**************************************************************************************
* CLASS DECLARATION
**************************************************************************************/

class BNO085
{
public:
BNO085(std::shared_ptr<SPI> const spi);

/* Do not publicly use those functions.
* They are used for the sensor hub HAL.
*/
int sh2_hal_read (uint8_t * pBuffer, unsigned len, uint32_t * t_us);
int sh2_hal_write (uint8_t * pBuffer, unsigned len);
uint32_t sh2_hal_getTimeUs();

private:
std::shared_ptr<SPI> const _spi;
std::chrono::steady_clock::time_point const _start;
sh2_Hal_t _sh2_hal;

void reset();
void init();
};
4 changes: 3 additions & 1 deletion main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,12 @@
#include <stdexcept>

#include "spi.h"
#include "bno085.h"

int main(int /* argc */, char ** /* argv */) try
{
auto spi = std::make_shared<SPI>("/dev/spidev1.0", SPI_MODE_0, 8, 1000000);
auto spi = std::make_shared<SPI>("/dev/spidev1.0", SPI_MODE_3, 8, 1*1000*1000UL);
auto bno085 = std::make_shared<BNO085>(spi);
return EXIT_SUCCESS;
}
catch (std::runtime_error const & err)
Expand Down
1 change: 1 addition & 0 deletions sh2
Submodule sh2 added at 884912

0 comments on commit 3aa45d8

Please sign in to comment.