Browse Source

uavcan module: extracted public module header for inclusion from other components

The module has some interfaces, that need to be known by external components (e.g. the IOCTL bases and device paths). These were defined in uavcan_main.hpp, which contains to much internal knowledge to be includable from other components.
sbg
Holger Steinhaus 9 years ago committed by Lorenz Meier
parent
commit
5acad450f8
  1. 1
      src/modules/uavcan/uavcan_main.cpp
  2. 71
      src/modules/uavcan/uavcan_module.hpp
  3. 9
      src/modules/uavcan/uavcan_servers.hpp

1
src/modules/uavcan/uavcan_main.cpp

@ -52,6 +52,7 @@ @@ -52,6 +52,7 @@
#include <drivers/drv_hrt.h>
#include <drivers/drv_pwm_output.h>
#include "uavcan_module.hpp"
#include "uavcan_main.hpp"
#include <uavcan/util/templates.hpp>

71
src/modules/uavcan/uavcan_module.hpp

@ -0,0 +1,71 @@ @@ -0,0 +1,71 @@
/****************************************************************************
*
* Copyright (c) 2014 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_config.h>
#include <drivers/device/device.h>
/**
* @file uavcan.hpp
*
* Public header for the UAVCAN module
*
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
* @author David Sidrane <david_s5@nscdg.com>
* @author Holger Steinhaus <holger@steinhaus-home.de>
*/
// firmware paths
#define UAVCAN_MAX_PATH_LENGTH (128 + 40)
#define UAVCAN_FIRMWARE_PATH "/fs/microsd/fw"
#define UAVCAN_ROMFS_FW_PATH "/etc/firmware/uavcan"
#define UAVCAN_ROMFS_FW_PREFIX "_"
// logging
#define UAVCAN_NODE_DB_PATH "/fs/microsd/uavcan.db"
#define UAVCAN_LOG_FILE UAVCAN_NODE_DB_PATH"/trace.log"
// device files
// TODO: split IOCTL interface in ESC and node related functionality, then change UAVCAN_DEVICE_PATH to "/dev/uavcan/node"
#define UAVCAN_DEVICE_PATH "/dev/uavcan/esc"
#define UAVCAN_ESC_DEVICE_PATH "/dev/uavcan/esc"
// ioctl interface
#define _UAVCAN_IOC(_n) (_IOC(_UAVCAN_IOCBASE, _n))
#define _UAVCAN_IOCBASE (0x4000) // IOCTL base for module UAVCAN
#define UAVCAN_IOCG_NODEID_INPROGRESS _UAVCAN_IOC(1) // query if node identification is in progress
// public prototypes
extern "C" __EXPORT int uavcan_main(int argc, char *argv[]);

9
src/modules/uavcan/uavcan_servers.hpp

@ -55,6 +55,7 @@ @@ -55,6 +55,7 @@
#include <uavcan/protocol/enumeration/Begin.hpp>
#include <uavcan/protocol/enumeration/Indication.hpp>
#include "uavcan_module.hpp"
#include "uavcan_virtual_can_driver.hpp"
/**
@ -66,14 +67,6 @@ @@ -66,14 +67,6 @@
* @author David Sidrane <david_s5@nscdg.com>
*/
#define UAVCAN_DEVICE_PATH "/dev/uavcan/esc"
#define UAVCAN_NODE_DB_PATH "/fs/microsd/uavcan.db"
#define UAVCAN_FIRMWARE_PATH "/fs/microsd/fw"
#define UAVCAN_ROMFS_FW_PATH "/etc/uavcan/fw"
#define UAVCAN_ROMFS_FW_PREFIX "_"
#define UAVCAN_MAX_PATH_LENGTH (128 + 40)
#define UAVCAN_LOG_FILE UAVCAN_NODE_DB_PATH"/trace.log"
/**
* A UAVCAN Server Sub node.
*/

Loading…
Cancel
Save