9 changed files with 283 additions and 1 deletions
@ -0,0 +1 @@
@@ -0,0 +1 @@
|
||||
./dsdlc_generated/ |
@ -0,0 +1,74 @@
@@ -0,0 +1,74 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
||||
# Author: Pavel Kirienko <pavel.kirienko@gmail.com>
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# UAVCAN <--> uORB bridge
|
||||
#
|
||||
|
||||
MODULE_COMMAND = uavcan
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
SRCS += uavcan_main.cpp \
|
||||
uavcan_clock.cpp
|
||||
|
||||
#
|
||||
# libuavcan
|
||||
#
|
||||
include $(UAVCAN_DIR)/libuavcan/include.mk |
||||
SRCS += $(LIBUAVCAN_SRC)
|
||||
# TODO fix include path
|
||||
INCLUDE_DIRS += $(LIBUAVCAN_INC) /media/storage/px4/Firmware/Build/px4fmu-v2_default.build/nuttx-export/include/cxx/
|
||||
EXTRADEFINES += -DUAVCAN_MEM_POOL_BLOCK_SIZE=56 \
|
||||
-DUAVCAN_TOSTRING=0 \
|
||||
-DUAVCAN_CPP_VERSION=UAVCAN_CPP03 \
|
||||
-DUAVCAN_IMPLEMENT_PLACEMENT_NEW=1
|
||||
|
||||
#
|
||||
# libuavcan drivers for STM32
|
||||
#
|
||||
include $(UAVCAN_DIR)/libuavcan_drivers/stm32/driver/include.mk |
||||
SRCS += $(LIBUAVCAN_STM32_SRC)
|
||||
INCLUDE_DIRS += $(LIBUAVCAN_STM32_INC)
|
||||
EXTRADEFINES += -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM_IFACES=1
|
||||
|
||||
#
|
||||
# Invoke DSDL compiler
|
||||
# TODO: Add make target for this, or invoke dsdlc manually.
|
||||
# The second option assumes that the generated headers shall be saved
|
||||
# under the version control, which may be undesirable.
|
||||
# The first option requires python3 and python3-mako for the sources to be built.
|
||||
#
|
||||
$(info $(shell $(LIBUAVCAN_DSDLC) $(UAVCAN_DSDL_DIR))) |
||||
INCLUDE_DIRS += dsdlc_generated
|
@ -0,0 +1,65 @@
@@ -0,0 +1,65 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2014 PX4 Development Team. All rights reserved. |
||||
* Author: Pavel Kirienko <pavel.kirienko@gmail.com> |
||||
* |
||||
* 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 <uavcan_stm32/uavcan_stm32.hpp> |
||||
#include <drivers/drv_hrt.h> |
||||
|
||||
namespace uavcan_stm32 |
||||
{ |
||||
namespace clock |
||||
{ |
||||
|
||||
uavcan::MonotonicTime getMonotonic() |
||||
{ |
||||
return uavcan::MonotonicTime::fromUSec(hrt_absolute_time()); |
||||
} |
||||
|
||||
uavcan::UtcTime getUtc() |
||||
{ |
||||
return uavcan::UtcTime(); |
||||
} |
||||
|
||||
void adjustUtc(uavcan::UtcDuration adjustment) |
||||
{ |
||||
(void)adjustment; |
||||
} |
||||
|
||||
uavcan::uint64_t getUtcUSecFromCanInterrupt() |
||||
{ |
||||
return 0; |
||||
} |
||||
|
||||
} |
||||
} |
||||
|
@ -0,0 +1,100 @@
@@ -0,0 +1,100 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2014 PX4 Development Team. All rights reserved. |
||||
* Author: Pavel Kirienko <pavel.kirienko@gmail.com> |
||||
* |
||||
* 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 <cstdlib> |
||||
#include <cstring> |
||||
#include <systemlib/err.h> |
||||
#include <systemlib/systemlib.h> |
||||
#include <arch/board/board.h> |
||||
#include "uavcan_main.hpp" |
||||
|
||||
extern "C" __EXPORT int uavcan_main(int argc, char *argv[]); |
||||
|
||||
namespace |
||||
{ |
||||
|
||||
uavcan_stm32::CanInitHelper<> can_driver; |
||||
|
||||
void print_usage() |
||||
{ |
||||
warnx("usage: uavcan start [can_bitrate]"); |
||||
} |
||||
|
||||
int test_thread(int argc, char *argv[]) |
||||
{ |
||||
stm32_configgpio(GPIO_CAN1_RX); |
||||
stm32_configgpio(GPIO_CAN1_TX); |
||||
stm32_configgpio(GPIO_CAN2_RX); |
||||
stm32_configgpio(GPIO_CAN2_TX); |
||||
int res = can_driver.init(1000000); |
||||
if (res < 0) |
||||
{ |
||||
errx(res, "CAN driver init failed"); |
||||
} |
||||
while (true) |
||||
{ |
||||
::sleep(1); |
||||
auto iface = static_cast<uavcan::ICanIface*>(can_driver.driver.getIface(0)); |
||||
res = iface->send(uavcan::CanFrame(), uavcan_stm32::clock::getMonotonic(), 0); |
||||
warnx("published %i, pending %u", res, can_driver.driver.getIface(0)->getRxQueueLength()); |
||||
} |
||||
return 0; |
||||
} |
||||
|
||||
} |
||||
|
||||
int uavcan_main(int argc, char *argv[]) |
||||
{ |
||||
if (argc < 2) { |
||||
print_usage(); |
||||
::exit(1); |
||||
} |
||||
|
||||
if (!std::strcmp(argv[1], "start")) { |
||||
static bool started = false; |
||||
if (started) |
||||
{ |
||||
warnx("already started"); |
||||
::exit(1); |
||||
} |
||||
started = true; |
||||
(void)task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 3000, |
||||
static_cast<main_t>(&test_thread), const_cast<const char**>(argv)); |
||||
return 0; |
||||
} else { |
||||
print_usage(); |
||||
::exit(1); |
||||
} |
||||
return 0; |
||||
} |
@ -0,0 +1,39 @@
@@ -0,0 +1,39 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2014 PX4 Development Team. All rights reserved. |
||||
* Author: Pavel Kirienko <pavel.kirienko@gmail.com> |
||||
* |
||||
* 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 <uavcan_stm32/uavcan_stm32.hpp> |
||||
|
||||
// ...
|
Loading…
Reference in new issue