delete aerotenna ocpoc

This commit is contained in:
Daniel Agar 2021-02-25 17:42:59 -05:00 committed by Lorenz Meier
parent 5f9a98e316
commit 7393d5d761
15 changed files with 7 additions and 690 deletions

View File

@ -17,7 +17,7 @@ pipeline {
]
def armhf_builds = [
target: ["aerotenna_ocpoc_default", "beaglebone_blue_default", "emlid_navio2_default", "px4_raspberrypi_default", "scumaker_pilotpi_default"],
target: [beaglebone_blue_default", "emlid_navio2_default", "px4_raspberrypi_default", "scumaker_pilotpi_default"],
image: docker_images.armhf,
archive: false
]

View File

@ -15,7 +15,6 @@ jobs:
strategy:
matrix:
config: [
aerotenna_ocpoc_default,
beaglebone_blue_default,
emlid_navio2_default,
px4_raspberrypi_default,

View File

@ -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:2021-02-04"
elif [[ $@ =~ .*ocpoc.* ]] || [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*beaglebone.* ]] || [[ $@ =~ .*pilotpi.default ]]; then
# aerotenna_ocpoc_default, beaglebone_blue_default, emlid_navio2_default, px4_raspberrypi_default, scumaker_pilotpi_default
elif [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*beaglebone.* ]] || [[ $@ =~ .*pilotpi.default ]]; then
# beaglebone_blue_default, emlid_navio2_default, px4_raspberrypi_default, scumaker_pilotpi_default
PX4_DOCKER_REPO="px4io/px4-dev-armhf:2021-02-04"
elif [[ $@ =~ .*pilotpi.arm64 ]]; then
# scumaker_pilotpi_arm64
@ -14,8 +14,8 @@ if [ -z ${PX4_DOCKER_REPO+x} ]; then
elif [[ $@ =~ .*eagle.* ]] || [[ $@ =~ .*excelsior.* ]]; then
# eagle, excelsior
PX4_DOCKER_REPO="lorenzmeier/px4-dev-snapdragon:2020-04-01"
elif [[ $@ =~ .*ocpoc.* ]] || [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*bebop.* ]]; then
# aerotenna_ocpoc_default, posix_rpi_cross, posix_bebop_default
elif [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*bebop.* ]]; then
# posix_rpi_cross, posix_bebop_default
PX4_DOCKER_REPO="px4io/px4-dev-armhf:2021-02-04"
elif [[ $@ =~ .*clang.* ]] || [[ $@ =~ .*scan-build.* ]]; then
# clang tools

View File

@ -1,34 +0,0 @@
############################################################################
#
# Copyright (c) 2018 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(adc)

View File

@ -1,36 +0,0 @@
############################################################################
#
# 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.
#
############################################################################
px4_add_library(arch_adc
adc.cpp
)

View File

@ -1,103 +0,0 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#include <board_config.h>
#include <drivers/drv_adc.h>
#include <px4_platform_common/log.h>
#include <fcntl.h>
#include <stdint.h>
#include <unistd.h>
#define ADC_SYSFS_PATH "/sys/bus/iio/devices/iio:device0"
#define ADC_MAX_CHAN 9
int _channels_fd[ADC_MAX_CHAN];
int px4_arch_adc_init(uint32_t base_address)
{
for (int i = 0; i < ADC_MAX_CHAN; i++) {
_channels_fd[i] = -1;
}
return 0;
}
void px4_arch_adc_uninit(uint32_t base_address)
{
for (int i = 0; i < ADC_MAX_CHAN; i++) {
::close(_channels_fd[i]);
_channels_fd[i] = -1;
}
}
uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel)
{
if (channel > ADC_MAX_CHAN) {
PX4_ERR("channel %d out of range: %d", channel, ADC_MAX_CHAN);
return UINT32_MAX; // error
}
// open channel if necessary
if (_channels_fd[channel] == -1) {
// ADC_SYSFS_PATH
char channel_path[strlen(ADC_SYSFS_PATH) + 20] {};
if (sprintf(channel_path, "%s/in_voltage%d_raw", ADC_SYSFS_PATH, channel) == -1) {
PX4_ERR("adc channel: %d\n", channel);
return UINT32_MAX; // error
}
_channels_fd[channel] = ::open(channel_path, O_RDONLY);
}
char buffer[10] {};
if (::pread(_channels_fd[channel], buffer, sizeof(buffer), 0) < 0) {
PX4_ERR("read channel %d failed", channel);
return UINT32_MAX; // error
}
return atoi(buffer);
}
float px4_arch_adc_reference_v()
{
return BOARD_ADC_POS_REF_V;
}
uint32_t px4_arch_adc_dn_fullcount()
{
return 1 << 12; // 12 bit ADC
}

View File

@ -1,99 +0,0 @@
add_definitions(
-D__PX4_LINUX
)
px4_add_board(
VENDOR aerotenna
MODEL ocpoc
LABEL default
PLATFORM posix
ARCHITECTURE cortex-a9
ROMFSROOT px4fmu_common
TOOLCHAIN arm-linux-gnueabihf
TESTING
SERIAL_PORTS
GPS1:/dev/ttyS3 # GPS/Compass #1 (OcPoC Port 6)
GPS2:/dev/ttyS7 # GPS/Compass #2 (OcPoC Port 7)
GPS3:/dev/ttyS1 # GPS/Compass #3 (OcPoC Port 9)
TEL1:/dev/ttyPS1 # Radio Telemetry (OcPoC Port 4)
TEL2:/dev/ttyS6 # uLanding Radar Altimeter (OcPoC Port 8)
TEL3:/dev/ttyS2 # (OcPoC Port 2)
TEL4:/dev/ttyS0 # uSharp-Patch (OcPoC Port 5)
DRIVERS
#barometer # all available barometer drivers
barometer/ms5611
batt_smbus
camera_capture
camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
gps
imu/invensense/mpu9250
lights/rgbled
linux_pwm_out
#magnetometer # all available magnetometer drivers
magnetometer/hmc5883
pwm_out_sim
rc_input
#telemetry # all available telemetry drivers
MODULES
airspeed_selector
attitude_estimator_q
battery_status
camera_feedback
commander
dataman
ekf2
events
flight_mode_manager
fw_att_control
fw_pos_control_l1
land_detector
landing_target_estimator
load_mon
local_position_estimator
logger
mavlink
mc_att_control
mc_hover_thrust_estimator
mc_pos_control
mc_rate_control
#micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih
#simulator
temperature_compensation
vmount
vtol_att_control
SYSTEMCMDS
esc_calib
led_control
mixer
motor_ramp
motor_test
param
perf
pwm
sd_bench
system_time
shutdown
tests # tests and test runner
#top
topic_listener
tune_control
uorb
ver
work_queue
EXAMPLES
fake_gps
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
hello
#hwtest # Hardware test
#matlab_csv_serial
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
rover_steering_control # Rover example app
)

View File

@ -1,38 +0,0 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#pragma once
#define SYSTEM_ADC_BASE 0 // not used
#define px4_arch_adc_temp_sensor_mask() (0)

View File

@ -1,38 +0,0 @@
############################################################################
#
# Copyright (c) 2017 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_library(drivers_board
board_pwm_out.cpp
i2c.cpp
spi.cpp
)

View File

@ -1,61 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2017 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 board_config.h
*
* Aerotenna Ocpoc internal definitions
*/
#pragma once
#define BOARD_OVERRIDE_UUID "OCPOC00000000000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_OCPOC
#define BOARD_BATTERY1_V_DIV (10.177939394f)
#define BOARD_MAX_LEDS 1 // Number of external LED's this board has
#define PX4_NUMBER_I2C_BUSES 4
#define PX4_I2C_BUS_LED 1
// ADC channels:
#define ADC_CHANNELS (1 << 8)
#define ADC_BATTERY_VOLTAGE_CHANNEL 8
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
#include <system_config.h>
#include <px4_platform_common/board_common.h>

View File

@ -1,113 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2017 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.
*
****************************************************************************/
#ifndef MODULE_NAME
#define MODULE_NAME "ocpoc_pwm_out"
#endif
#include "board_pwm_out.h"
#include <px4_platform_common/log.h>
#include <fcntl.h>
#include <sys/mman.h>
#include <unistd.h>
using namespace pwm_out;
#define RCOUT_ZYNQ_PWM_BASE 0x43c00000
static const int TICK_PER_US = 50;
static const int FREQUENCY_PWM = 400;
static const int TICK_PER_S = 50000000;
OcpocMmapPWMOut::OcpocMmapPWMOut(int max_num_outputs)
{
_num_outputs = max_num_outputs;
if (_num_outputs > MAX_ZYNQ_PWMS) {
PX4_WARN("number of outputs too large. Setting to %i", MAX_ZYNQ_PWMS);
_num_outputs = MAX_ZYNQ_PWMS;
}
}
OcpocMmapPWMOut::~OcpocMmapPWMOut()
{
if (_shared_mem_cmd) {
munmap((void *)_shared_mem_cmd, 0x1000);
}
}
unsigned long OcpocMmapPWMOut::freq2tick(uint16_t freq_hz)
{
unsigned long duty = TICK_PER_S / (unsigned long)freq_hz;
return duty;
}
int OcpocMmapPWMOut::init()
{
uint32_t mem_fd = open(_device, O_RDWR | O_SYNC);
_shared_mem_cmd = (struct pwm_cmd *) mmap(0, 0x1000, PROT_READ | PROT_WRITE,
MAP_SHARED, mem_fd, RCOUT_ZYNQ_PWM_BASE);
close(mem_fd);
if (_shared_mem_cmd == nullptr) {
PX4_ERR("initialize pwm pointer failed.");
return -1;
}
for (int i = 0; i < _num_outputs; ++i) {
_shared_mem_cmd->periodhi[i].period = freq2tick(FREQUENCY_PWM);
_shared_mem_cmd->periodhi[i].hi = freq2tick(FREQUENCY_PWM) / 2;
PX4_DEBUG("Output values: %d, %d", _shared_mem_cmd->periodhi[i].period, _shared_mem_cmd->periodhi[i].hi);
}
return 0;
}
int OcpocMmapPWMOut::send_output_pwm(const uint16_t *pwm, int num_outputs)
{
if (num_outputs > _num_outputs) {
num_outputs = _num_outputs;
}
//convert this to duty_cycle in ns
for (int i = 0; i < num_outputs; ++i) {
//n = ::asprintf(&data, "%u", pwm[i] * 1000);
//::write(_pwm_fd[i], data, n);
_shared_mem_cmd->periodhi[i].hi = TICK_PER_US * pwm[i];
//printf("ch:%d, val:%d*%d ", ch, period_us, TICK_PER_US);
}
return 0;
}

View File

@ -1,77 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2017 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.
*
****************************************************************************/
#pragma once
#include <px4_platform/pwm_out_base.h>
#define BOARD_PWM_OUT_IMPL OcpocMmapPWMOut
namespace pwm_out
{
/**
** class OcpocMmapPWMOut
* PWM output class for Aerotenna OcPoC via mmap
*/
class OcpocMmapPWMOut : public PWMOutBase
{
public:
OcpocMmapPWMOut(int max_num_outputs);
virtual ~OcpocMmapPWMOut();
int init() override;
int send_output_pwm(const uint16_t *pwm, int num_outputs) override;
private:
static unsigned long freq2tick(uint16_t freq_hz);
static constexpr int MAX_ZYNQ_PWMS = 8; /**< maximum number of pwm channels */
// Period|Hi 32 bits each
struct s_period_hi {
uint32_t period;
uint32_t hi;
};
struct pwm_cmd {
struct s_period_hi periodhi[MAX_ZYNQ_PWMS];
};
volatile struct pwm_cmd *_shared_mem_cmd = nullptr;
static constexpr const char *_device = "/dev/mem";
int _num_outputs;
};
}

View File

@ -1,41 +0,0 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#include <px4_arch/i2c_hw_description.h>
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusExternal(2), // i2c-2: Air Data Probe or I2C Splitter
initI2CBusExternal(4), // i2c-4: GPS/Compass #1
initI2CBusExternal(5), // i2c-5: GPS/Compass #2
initI2CBusExternal(3), // i2c-3: GPS/Compass #3
};

View File

@ -1,42 +0,0 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#include <px4_arch/spi_hw_description.h>
#include <drivers/drv_sensor.h>
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(1, {
initSPIDevice(DRV_IMU_DEVTYPE_MPU9250, 0),
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, 1),
}),
};

View File

@ -339,11 +339,11 @@ typedef enum PX4_SOC_ARCH_ID_t {
PX4_SOC_ARCH_ID_EAGLE = 0x1001,
PX4_SOC_ARCH_ID_QURT = 0x1002,
PX4_SOC_ARCH_ID_OCPOC = 0x1003,
PX4_SOC_ARCH_ID_RPI = 0x1004,
PX4_SOC_ARCH_ID_SIM = 0x1005,
PX4_SOC_ARCH_ID_SITL = 0x1006,
PX4_SOC_ARCH_ID_BEBOP = 0x1007,
PX4_SOC_ARCH_ID_BBBLUE = 0x1008,
} PX4_SOC_ARCH_ID_t;