Skip to content

Commit

Permalink
boards: bluerobotics: Add navigator board support
Browse files Browse the repository at this point in the history
  • Loading branch information
JoaoMario109 committed Nov 21, 2024
1 parent 47a9fec commit b610b94
Show file tree
Hide file tree
Showing 13 changed files with 652 additions and 2 deletions.
5 changes: 5 additions & 0 deletions .vscode/cmake-variants.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -221,6 +221,11 @@ CONFIG:
buildType: MinSizeRel
settings:
CONFIG: bitcraze_crazyflie_default
bluerobotics_navigator_default:
short: bluerobotics_navigator
buildType: MinSizeRel
settings:
CONFIG: bluerobotics_navigator_default
cuav_can-gps-v1_default:
short: cuav_can-gps-v1_default
buildType: MinSizeRel
Expand Down
4 changes: 2 additions & 2 deletions Tools/docker_run.sh
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@ if [ -z ${PX4_DOCKER_REPO+x} ]; then
if [[ $@ =~ .*px4_fmu.* ]]; then
# nuttx-px4fmu-v{1,2,3,4,5}
PX4_DOCKER_REPO="px4io/px4-dev-nuttx-focal:2022-08-12"
elif [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*beaglebone.* ]] || [[ $@ =~ .*pilotpi.default ]]; then
# beaglebone_blue_default, emlid_navio2_default, px4_raspberrypi_default, scumaker_pilotpi_default
elif [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*beaglebone.* ]] || [[ $@ =~ .*pilotpi.default ]] || [[ $@ =~ .*navigator.* ]]; then
# beaglebone_blue_default, emlid_navio2_default, px4_raspberrypi_default, scumaker_pilotpi_default, bluerobotics_navigator_default
PX4_DOCKER_REPO="px4io/px4-dev-armhf:2023-06-26"
elif [[ $@ =~ .*pilotpi.arm64 ]]; then
# scumaker_pilotpi_arm64
Expand Down
34 changes: 34 additions & 0 deletions boards/bluerobotics/navigator/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
############################################################################
#
# Copyright (c) 2024 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################

add_subdirectory(neopixel)
53 changes: 53 additions & 0 deletions boards/bluerobotics/navigator/cmake/upload.cmake
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
############################################################################
#
# Copyright (c) 2020 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################

if(DEFINED ENV{AUTOPILOT_HOST})
set(AUTOPILOT_HOST $ENV{AUTOPILOT_HOST})
else()
set(AUTOPILOT_HOST "raspberrypi")
endif()

if(DEFINED ENV{AUTOPILOT_USER})
set(AUTOPILOT_USER $ENV{AUTOPILOT_USER})
else()
set(AUTOPILOT_USER "pi")
endif()

add_custom_target(upload
COMMAND rsync -arh --progress
${CMAKE_RUNTIME_OUTPUT_DIRECTORY} ${PX4_SOURCE_DIR}/posix-configs/rpi/navigator/*.config ${PX4_BINARY_DIR}/etc # source
"${AUTOPILOT_USER}@${AUTOPILOT_HOST}:/home/${AUTOPILOT_USER}/px4" # destination
DEPENDS px4
COMMENT "uploading px4"
USES_TERMINAL
)
78 changes: 78 additions & 0 deletions boards/bluerobotics/navigator/default.px4board
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
CONFIG_PLATFORM_POSIX=y
CONFIG_BOARD_LINUX_TARGET=y
CONFIG_BOARD_TESTING=y
CONFIG_BOARD_TOOLCHAIN="arm-linux-gnueabihf"
CONFIG_BOARD_ARCHITECTURE="cortex-a53"
CONFIG_DRIVERS_ADC_ADS1115=y
CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_LIGHTS_NEOPIXEL=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
CONFIG_DRIVERS_BAROMETER_BMP280=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_MAGNETOMETER_MEMSIC_MMC5983MA=y
CONFIG_DRIVERS_MAGNETOMETER_AKM_AK09916=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_PCA9685_USE_EXTERNAL_CRYSTAL=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
CONFIG_COMMON_RC=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL=y
CONFIG_MODULES_FW_RATE_CONTROL=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DYN=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SHUTDOWN=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_DYN_HELLO=y
CONFIG_EXAMPLES_FAKE_GPS=y
CONFIG_EXAMPLES_HELLO=y
CONFIG_EXAMPLES_PX4_MAVLINK_DEBUG=y
CONFIG_EXAMPLES_PX4_SIMPLE_APP=y
CONFIG_EXAMPLES_WORK_ITEM=y
7 changes: 7 additions & 0 deletions boards/bluerobotics/navigator/init/rc.board_defaults
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------

# 1K + 4.7K
param set-default BAT1_V_DIV 5.7
36 changes: 36 additions & 0 deletions boards/bluerobotics/navigator/neopixel/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
############################################################################
#
# Copyright (c) 2024 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################

px4_add_library(arch_srgbled_dma
srgbled_impl.cpp
)
155 changes: 155 additions & 0 deletions boards/bluerobotics/navigator/neopixel/srgbled_impl.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,155 @@
/****************************************************************************
*
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/

/**
* @file srgbled_impl.cpp
*
* Implementation of functions to control NeoPixel LEDs on the BlueRobotics Navigator for the neopixel driver.
*
* Definitions:
* - BOARD_HAS_N_S_RGB_LED: Number of NeoPixel LEDs on the Navigator.
* - BOARD_RGB_SPI_BUS: SPI bus connected to the NeoPixel data line.
* - BOARD_RGB_SPI_FREQ: SPI bus frequency for the NeoPixel connection.
*/

#include <board_config.h>
#include <drivers/drv_neopixel.h>
#include <px4_platform_common/i2c_spi_buses.h>
#include <px4_platform_common/log.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/sem.h>

#if defined(BOARD_HAS_N_S_RGB_LED)

#if !defined(BOARD_RGB_SPI_BUS)
# error BOARD_RGB_SPI_BUS must be defined to use the NeoPixel driver implementation for the BlueRobotics Navigator
#endif
#if !defined(BOARD_RGB_SPI_FREQ)
# error BOARD_RGB_SPI_FREQ must be defined to use the NeoPixel driver implementation for the BlueRobotics Navigator
#endif

#define LED_T0 0b11000000
#define LED_T1 0b11110000

class NavigatorLED : public device::SPI
{
public:
NavigatorLED();
~NavigatorLED() override = default;

int init();
int write(uint8_t red, uint8_t green, uint8_t blue);
int deinit();

protected:
void _setup_data(uint8_t red, uint8_t green, uint8_t blue);

private:
uint8_t _data[24];
px4_sem_t _sem;
};

NavigatorLED::NavigatorLED() :
// By default we don't use the CS line and MODE must be 0 for compatibility with Raspberry Pi
SPI(DRV_DEVTYPE_UNUSED, "navigator-neopixel", BOARD_RGB_SPI_BUS, 0, SPIDEV_MODE0, BOARD_RGB_SPI_FREQ)
{
px4_sem_init(&_sem, 0, 1);
}

int NavigatorLED::init()
{
int ret = SPI::init();

if (ret != PX4_OK) {
PX4_ERR("Neopixel SPI init failed");
return ret;
}

return PX4_OK;
}

void NavigatorLED::_setup_data(uint8_t red, uint8_t green, uint8_t blue)
{
for (uint8_t i = 0; i < 8; i++) {
_data[i] = (green & (1<<(7-i))) ? LED_T1 : LED_T0;
}
for (uint8_t i = 0; i < 8; i++) {
_data[8 + i] = (red & (1<<(7-i))) ? LED_T1 : LED_T0;
}
for (uint8_t i = 0; i < 8; i++) {
_data[16 + i] = (blue & (1<<(7-i))) ? LED_T1 : LED_T0;
}
}

int NavigatorLED::write(uint8_t red, uint8_t green, uint8_t blue)
{
_setup_data(red, green, blue);

px4_sem_wait(&_sem);

int ret = transfer(_data, nullptr, sizeof(_data));

px4_sem_post(&_sem);

if (ret != PX4_OK) {
PX4_ERR("Failed to write data to NeoPixel %d", ret);
}

return ret;
}

int NavigatorLED::deinit()
{
PX4_INFO("Neopixel deinitialized");
return PX4_OK;
}

// Neopixel driver impl

NavigatorLED navigator_led;

int neopixel_init(neopixel::NeoLEDData *led_data, int number_of_packages)
{
return navigator_led.init();
}

int neopixel_write(neopixel::NeoLEDData *led_data, int number_of_packages)
{
return navigator_led.write(led_data->R(), led_data->G(), led_data->B());
}

int neopixel_deinit()
{
return navigator_led.deinit();
}
#endif // defined(BOARD_HAS_N_S_RGB_LED)
Loading

0 comments on commit b610b94

Please sign in to comment.