diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..5213bbc --- /dev/null +++ b/.gitmodules @@ -0,0 +1,6 @@ +[submodule "src/rov/rov_bno085/sh2"] + path = src/rov/rov_bno085/sh2 + url = https://github.com/ceva-dsp/sh2/ +[submodule "src/rov/rov_bno085/jetgpio"] + path = src/rov/rov_bno085/jetgpio + url = https://github.com/Rubberazer/JETGPIO diff --git a/src/rov/rov_bno085/CMakeLists.txt b/src/rov/rov_bno085/CMakeLists.txt new file mode 100644 index 0000000..efe8a44 --- /dev/null +++ b/src/rov/rov_bno085/CMakeLists.txt @@ -0,0 +1,58 @@ +cmake_minimum_required(VERSION 3.16) +project(rov_bno085) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +# uncomment the following section in order to fill in +# further dependencies manually. +# find_package( REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) +find_package(std_srvs REQUIRED) +find_package(sensor_msgs REQUIRED) + +add_executable(bno085 src/main.cpp +src/bno08x_node.cpp +src/bno08x_driver.cpp +sh2/euler.c +sh2/sh2_SensorValue.c +sh2/sh2_util.c +sh2/sh2.c +sh2/shtp.c +jetgpio/orin.c +) +target_include_directories(bno085 PUBLIC + $ + $ + $ + $) +target_compile_features(bno085 PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 + +ament_target_dependencies(bno085 + rclcpp + std_msgs + std_srvs + sensor_msgs +) + + +install(TARGETS bno085 + DESTINATION lib/${PROJECT_NAME}) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # comment the line when a copyright and license is added to all source files + set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # comment the line when this package is in a git repo and when + # a copyright and license is added to all source files + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/src/rov/rov_bno085/include/rov_bno085/bno08x_driver.hpp b/src/rov/rov_bno085/include/rov_bno085/bno08x_driver.hpp new file mode 100644 index 0000000..f0fe776 --- /dev/null +++ b/src/rov/rov_bno085/include/rov_bno085/bno08x_driver.hpp @@ -0,0 +1,59 @@ +#ifndef BNO08X_DRIVER_HPP +#define BNO08X_DRIVER_HPP + +#include + +extern "C" { +#include "sh2_SensorValue.h" +#include "sh2_hal.h" +} + +#define I2C_DEFAULT_ADDRESS 0x4A +#define DEFAULT_RESET_PIN 33 +#define DEFAULT_INTERRUPT_PIN 31 + +#define PAC_ON_STAIRS 8 +#define PAC_OPTION_COUNT 9 + +// looks like this works? https://github.com/Rubberazer/JETGPIO?tab=readme-ov-file +// https://github.com/Rubberazer/Jetclocks +// ^^^^ TODO: NEED TO INSTALL JETCLOCKS ON ORIN + +// see https://github.com/adafruit/Adafruit_BNO08x/blob/master/src/Adafruit_BNO08x.cpp +// for inspiration +class BNO08X { +public: + BNO08X(uint8_t reset_pin = DEFAULT_RESET_PIN, uint8_t interrupt_pin = DEFAULT_INTERRUPT_PIN); + BNO08X(BNO08X&&) = delete; + BNO08X operator=(BNO08X&) = delete; + ~BNO08X(); + + bool makeI2C(uint8_t address = I2C_DEFAULT_ADDRESS, int32_t sensor_id = 0) {return false;}; // NOTE: UNIMPLEMENTED + bool makeUART(int32_t sensor_id = 0) {return false;}; // NOTE: UNIMPLEMENTED + bool makeSPI(int32_t sensor_id = 0); + + // reset the device using the reset pin + void hardwareReset(void); + // check if a reset has occured + bool wasReset(void); + + // enable the given report type + bool enableReport(sh2_SensorId_t sensor_id, uint32_t interval_us = 10000); + // fill the given sensor value object with a new report + bool getSensorEvent(sh2_SensorValue_t* value); +private: + sh2_ProductIds_t product_ids; + + int fd; + + uint8_t reset_pin; + uint8_t interrupt_pin; + +protected: + // called post i2c/spi init + virtual bool _init(int32_t sensor_id); + + sh2_Hal_t _HAL; +}; + +#endif \ No newline at end of file diff --git a/src/rov/rov_bno085/include/rov_bno085/bno08x_node.hpp b/src/rov/rov_bno085/include/rov_bno085/bno08x_node.hpp new file mode 100644 index 0000000..64101e5 --- /dev/null +++ b/src/rov/rov_bno085/include/rov_bno085/bno08x_node.hpp @@ -0,0 +1,41 @@ +#ifndef BNO08X_NODE_HPP +#define BNO08X_NODE_HPP + +#include + +#include +#include +#include +#include +#include +// TODO include quat definition or just vectord? + +#include "rov_bno085/bno08x_driver.hpp" + +class BNO08X_Node : public rclcpp::Node { +public: + BNO08X_Node(uint8_t bus = 1); + BNO08X_Node(const BNO08X_Node&) = delete; + BNO08X_Node(BNO08X_Node&&) = default; + ~BNO08X_Node(); + + void open(); + void close(); + void reset(); + +private: + void pollBNO(); + void publishBNOData(); + + rclcpp::Publisher::SharedPtr pub_accel_gyro; + rclcpp::Publisher::SharedPtr pub_mag; + rclcpp::Publisher::SharedPtr pub_temp; + + rclcpp::TimerBase::SharedPtr timer_poll_bno; + + BNO08X bno08x; + + int spi_fd; +}; + +#endif \ No newline at end of file diff --git a/src/rov/rov_bno085/jetgpio b/src/rov/rov_bno085/jetgpio new file mode 160000 index 0000000..51d7aca --- /dev/null +++ b/src/rov/rov_bno085/jetgpio @@ -0,0 +1 @@ +Subproject commit 51d7aca988c5d8cfbe1a66146ba1491cdd1a571d diff --git a/src/rov/rov_bno085/package.xml b/src/rov/rov_bno085/package.xml new file mode 100644 index 0000000..bdad3f5 --- /dev/null +++ b/src/rov/rov_bno085/package.xml @@ -0,0 +1,18 @@ + + + + rov_bno085 + 0.0.0 + TODO: Package description + yameat + TODO: License declaration + + ament_cmake + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/src/rov/rov_bno085/sh2 b/src/rov/rov_bno085/sh2 new file mode 160000 index 0000000..b514b1e --- /dev/null +++ b/src/rov/rov_bno085/sh2 @@ -0,0 +1 @@ +Subproject commit b514b1e2586ddc195e553dac89fc94c637b25298 diff --git a/src/rov/rov_bno085/src/bno08x_driver.cpp b/src/rov/rov_bno085/src/bno08x_driver.cpp new file mode 100644 index 0000000..aea7a3d --- /dev/null +++ b/src/rov/rov_bno085/src/bno08x_driver.cpp @@ -0,0 +1,347 @@ +#include "rov_bno085/bno08x_driver.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "jetgpio.h" + +extern "C" { +#include "sh2.h" +#include "sh2_err.h" +} + +#define SPIDEVICE "/dev/spidev1.0" + +// HAL garbage +static sh2_SensorValue_t *_sensor_value = NULL; +static bool _reset_occurred = false; + +// TODO: implement +// static int i2chal_write(sh2_Hal_t *self, uint8_t *pBuffer, unsigned len); +// static int i2chal_read(sh2_Hal_t *self, uint8_t *pBuffer, unsigned len, uint32_t *t_us); +// static void i2chal_close(sh2_Hal_t *self); +// static int i2chal_open(sh2_Hal_t *self); + +// TODO: implement +// static int uarthal_write(sh2_Hal_t *self, uint8_t *pBuffer, unsigned len); +// static int uarthal_read(sh2_Hal_t *self, uint8_t *pBuffer, unsigned len, uint32_t *t_us); +// static void uarthal_close(sh2_Hal_t *self); +// static int uarthal_open(sh2_Hal_t *self); + +static bool spihal_wait_for_int(void); +static int spihal_write(sh2_Hal_t *self, uint8_t *pBuffer, unsigned len); +static int spihal_read(sh2_Hal_t *self, uint8_t *pBuffer, unsigned len, uint32_t *t_us); +static void spihal_close(sh2_Hal_t *self); +static int spihal_open(sh2_Hal_t *self); +static uint8_t spi_mode = SPI_MODE_3; +static uint8_t spi_bits_per_word = 8; +static uint32_t spi_speed = 1e6; // 1 MHz +static uint8_t spi_lsb_first = 0; +static uint16_t spi_delay = 0; +static std::chrono::time_point spi_start; + +static uint32_t hal_getTimeUs(sh2_Hal_t *self); +static void hal_callback(void *cookie, sh2_AsyncEvent_t *pEvent); +static void sensorHandler(void *cookie, sh2_SensorEvent_t *pEvent); +static void hal_hardwareReset(void); + +// shared stuff +static int _fd; +static unsigned int _reset_pin; +static unsigned int _interrupt_pin; + +BNO08X::BNO08X(uint8_t reset_pin, uint8_t interrupt_pin) { + int ret; + ret = gpioInitialise(); + + if (ret < 0) { + printf("Jetgpio initialization failed with errco %d\n", ret); + throw std::logic_error("Jetgpio failed to initalize"); + } + + // setup reset pin as output + this->reset_pin = reset_pin; + _reset_pin = this->reset_pin; + ret = gpioSetMode(reset_pin, JET_OUTPUT); + + // setup "interrupt" pin as input + this->interrupt_pin = interrupt_pin; + _interrupt_pin = this->interrupt_pin; + ret = gpioSetMode(interrupt_pin, JET_INPUT); + + // spi by default + if (!makeSPI()) { + printf("Could not initialize BNO085\n"); + exit(1); + } + + printf("Successfully initialized!\n"); +} + +BNO08X::~BNO08X() { + gpioTerminate(); +} + +bool BNO08X::makeSPI(int32_t sensor_id) { + // if file descriptor is in use, we need to close it + if (fd != -1) { + close(fd); + // TODO: if uart and i2c have local fds, invalidate them now + } + + // open the spi device + fd = open(SPIDEVICE, O_RDWR); + if (fd < 0) { + printf("Unable to open SPI device"); + return false; + } + _fd = fd; + + // set spi mode + if (ioctl(fd, SPI_IOC_WR_MODE, &spi_mode) == -1) { + printf("Unable to set SPI mode"); + return false; + } + + // set bits per word + if (ioctl(fd, SPI_IOC_WR_BITS_PER_WORD, &spi_bits_per_word) == -1) { + printf("Unable to set bits per word"); + return false; + } + + // set max speed + if (ioctl(fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed) == -1) { + printf("Unable to set max speed"); + return false; + } + + // set bit order + if (ioctl(fd, SPI_IOC_WR_LSB_FIRST, &spi_lsb_first) == -1) { + printf("Unable to set bitorder to msb first"); + return false; + } + + _HAL.open = spihal_open; + _HAL.close = spihal_close; + _HAL.read = spihal_read; + _HAL.write = spihal_write; + _HAL.getTimeUs = hal_getTimeUs; + + spi_start = std::chrono::high_resolution_clock::now(); + + return true; +} + +bool BNO08X::_init(int32_t sensor_id) { + int status; + + hardwareReset(); + + // open SH2 + status = sh2_open(&_HAL, hal_callback, NULL); + if (status != SH2_OK) { + return false; + } + + // check connection + memset(&product_ids, 0, sizeof(product_ids)); + status = sh2_getProdIds(&product_ids); + if (status != SH2_OK) { + return false; + } + + // register sensor listener + sh2_setSensorCallback(sensorHandler, NULL); + + return true; +} + +void BNO08X::hardwareReset(void) { + hal_hardwareReset(); +} + +bool BNO08X::wasReset(void) { + bool x = _reset_occurred; + _reset_occurred = false; + return x; +} + +bool BNO08X::enableReport(sh2_SensorId_t sensor_id, uint32_t interval_us) { + static sh2_SensorConfig_t config; + + // sane defaults + config.changeSensitivityEnabled = false; + config.wakeupEnabled = false; + config.changeSensitivityRelative = false; + config.alwaysOnEnabled = false; + config.changeSensitivity = 0; + config.batchInterval_us = 0; + config.sensorSpecific = 0; + + config.reportInterval_us = interval_us; + int status = sh2_setSensorConfig(sensor_id, &config); + + if (status != SH2_OK) { + return false; + } + return true; +} + +bool BNO08X::getSensorEvent(sh2_SensorValue_t *value) { + _sensor_value = value; + value->timestamp = 0; + + sh2_service(); + + // check if there were new events + if (value->timestamp == 0 && value->sensorId != SH2_GYRO_INTEGRATED_RV) { + return false; + } + + return true; +} + + +static int spi_transfer(int fd, uint8_t* tx_buf, uint8_t* rx_buf, size_t len) { + struct spi_ioc_transfer tr{}; + memset(&tr, 0, sizeof(tr)); + tr.tx_buf = reinterpret_cast(tx_buf); + tr.rx_buf = reinterpret_cast(rx_buf); + tr.len = len; + tr.speed_hz = spi_speed; + tr.delay_usecs = spi_delay; + tr.bits_per_word = spi_bits_per_word; + + int ret = ioctl(fd, SPI_IOC_MESSAGE(1), &tr); + if (ret < 1) { + perror("SPI_IOC_MESSAGE failed"); + return -1; + } + + return 0; +} + +static bool spihal_wait_for_int(void) { + // this is actually really stupid + // does chip interrupt within 0.5 seconds? + for (int i = 0; i < 500; i++) { + if (gpioRead(_interrupt_pin)) { + return true; + } + std::this_thread::sleep_for(std::chrono::milliseconds(1)); + } + + // if chip does not interrupt, reset it + hal_hardwareReset(); + + return false; +} + +static int spihal_write(sh2_Hal_t *self, uint8_t *pBuffer, unsigned len) { + static uint8_t rx[4] = {0}; + if (!spihal_wait_for_int()) { + return 0; + } + + memset(rx, 0, sizeof(rx)); + int ret = spi_transfer(_fd, pBuffer, rx, len); + + // adafruit doesnt do this? + // if (ret < 0) { + // return 0; + // } + + return len; +} + +static int spihal_read(sh2_Hal_t *self, uint8_t *pBuffer, unsigned len, uint32_t *t_us) { + static uint16_t packet_size = 0; + static uint8_t tx[4] = {0}; + if (!spihal_wait_for_int()) { + return 0; + } + + // read spi + memset(tx, 0, sizeof(tx)); + int ret = spi_transfer(_fd, tx, pBuffer, 4); + if (ret < 0) { + return 0; + } + + // determine amount to read + packet_size = static_cast(pBuffer[0]) | (static_cast(pBuffer[1]) << 8); + // unset continue bit + packet_size &= 0x8000; + + if (packet_size > len) { + return 0; + } + + if (!spihal_wait_for_int()) { + return 0; + } + + // read packet_size bytes into pBuffer + memset(tx, 0, sizeof(tx)); + ret = spi_transfer(_fd, tx, pBuffer, packet_size); + if (ret < 0) { + return 0; + } + + // return how many bytes were read + return packet_size; +} + +static void spihal_close(sh2_Hal_t *self) { + // does nothing +} + +static int spihal_open(sh2_Hal_t *self) { + spihal_wait_for_int(); + + return 0; +} + +uint32_t hal_getTimeUs(sh2_Hal_t *self) { + auto tp = std::chrono::high_resolution_clock::now(); + // ~1 hour 71 minutes before it overflows.... + int64_t time = std::chrono::duration_cast(tp - spi_start).count(); + // handle 32bit overflow by wrapping back to 0 + if (time > UINT32_MAX) { + time = time - UINT32_MAX; + } + + return static_cast(time); +} + +void hal_callback(void *cookie, sh2_AsyncEvent_t *pEvent) { + if (pEvent->eventId == SH2_RESET) { + _reset_occurred = true; + } +} + +void sensorHandler(void *cookie, sh2_SensorEvent_t *pEvent) { + int ret; + ret = sh2_decodeSensorEvent(_sensor_value, pEvent); + + if (ret != SH2_OK) { + printf("BNO08x - Error decoding sensor event\n"); + _sensor_value->timestamp = 0; + return; + } +} + +void hal_hardwareReset(void) { + gpioWrite(_reset_pin, 1); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + gpioWrite(_reset_pin, 0); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + gpioWrite(_reset_pin, 1); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); +} \ No newline at end of file diff --git a/src/rov/rov_bno085/src/bno08x_node.cpp b/src/rov/rov_bno085/src/bno08x_node.cpp new file mode 100644 index 0000000..61c6ea8 --- /dev/null +++ b/src/rov/rov_bno085/src/bno08x_node.cpp @@ -0,0 +1,26 @@ +#include "rov_bno085/bno08x_driver.hpp" +#include "rov_bno085/bno08x_node.hpp" + +BNO08X_Node::BNO08X_Node(uint8_t bus) : Node("bno08x") { + +} + +BNO08X_Node::~BNO08X_Node() { + +} + +void BNO08X_Node::open() { + +} + +void BNO08X_Node::close() { + +} + +void BNO08X_Node::reset() { + +} + +void BNO08X_Node::publishBNOData() { + +} \ No newline at end of file diff --git a/src/rov/rov_bno085/src/main.cpp b/src/rov/rov_bno085/src/main.cpp new file mode 100644 index 0000000..4358937 --- /dev/null +++ b/src/rov/rov_bno085/src/main.cpp @@ -0,0 +1,8 @@ +#include "rov_bno085/bno08x_node.hpp" + +int main(int argc, char** argv) { + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} \ No newline at end of file