mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-21 08:17:35 +08:00
@@ -48,3 +48,5 @@ unittests/build
|
||||
.vagrant
|
||||
*.pretty
|
||||
xcode
|
||||
src/platforms/posix/px4_messages/
|
||||
src/platforms/qurt/px4_messages/
|
||||
|
||||
+10
-6
@@ -60,18 +60,22 @@ env:
|
||||
script:
|
||||
- ccache -z
|
||||
- arm-none-eabi-gcc --version
|
||||
- echo 'Running Tests..' && echo -en 'travis_fold:start:script.1\\r'
|
||||
- echo 'Building POSIX Firmware..' && echo -en 'travis_fold:start:script.1\\r'
|
||||
- make posix -j4
|
||||
- ccache -s
|
||||
- echo -en 'travis_fold:end:script.1\\r'
|
||||
- echo 'Running Tests..' && echo -en 'travis_fold:start:script.2\\r'
|
||||
- make tests
|
||||
- cat src/modules/systemlib/mixer/mixer_multirotor.generated.h
|
||||
- echo -en 'travis_fold:end:script.1\\r'
|
||||
- echo 'Building NuttX..' && echo -en 'travis_fold:start:script.2\\r'
|
||||
- echo -en 'travis_fold:end:script.2\\r'
|
||||
- echo 'Building NuttX..' && echo -en 'travis_fold:start:script.3\\r'
|
||||
- make archives
|
||||
- ccache -s
|
||||
- echo -en 'travis_fold:end:script.2\\r'
|
||||
- echo 'Building Firmware..' && echo -en 'travis_fold:start:script.3\\r'
|
||||
- echo -en 'travis_fold:end:script.3\\r'
|
||||
- echo 'Building NuttX Firmware..' && echo -en 'travis_fold:start:script.4\\r'
|
||||
- make -j4
|
||||
- ccache -s
|
||||
- echo -en 'travis_fold:end:script.3\\r'
|
||||
- echo -en 'travis_fold:end:script.4\\r'
|
||||
- zip Firmware.zip Images/*.px4
|
||||
|
||||
after_script:
|
||||
|
||||
@@ -53,13 +53,13 @@ export GIT_DESC
|
||||
#
|
||||
# Canned firmware configurations that we (know how to) build.
|
||||
#
|
||||
KNOWN_CONFIGS := $(subst config_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)config_*.mk))))
|
||||
KNOWN_CONFIGS := $(subst config_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)/$(PX4_TARGET_OS)/config_*.mk))))
|
||||
CONFIGS ?= $(KNOWN_CONFIGS)
|
||||
|
||||
#
|
||||
# Boards that we (know how to) build NuttX export kits for.
|
||||
#
|
||||
KNOWN_BOARDS := $(subst board_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)board_*.mk))))
|
||||
KNOWN_BOARDS := $(subst board_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)/$(PX4_TARGET_OS)/board_*.mk))))
|
||||
BOARDS ?= $(KNOWN_BOARDS)
|
||||
|
||||
#
|
||||
@@ -97,6 +97,7 @@ upload:
|
||||
endif
|
||||
endif
|
||||
|
||||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
#
|
||||
# Built products
|
||||
#
|
||||
@@ -209,6 +210,7 @@ menuconfig:
|
||||
@$(ECHO) ""
|
||||
@$(ECHO) "The menuconfig goal must be invoked without any other goal being specified"
|
||||
@$(ECHO) ""
|
||||
|
||||
endif
|
||||
|
||||
$(NUTTX_SRC): checksubmodules
|
||||
@@ -216,6 +218,20 @@ $(NUTTX_SRC): checksubmodules
|
||||
$(UAVCAN_DIR):
|
||||
$(Q) (./Tools/check_submodules.sh)
|
||||
|
||||
endif
|
||||
|
||||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
# TODO
|
||||
# Move the above nuttx specific rules into $(PX4_BASE)makefiles/firmware_nuttx.mk
|
||||
endif
|
||||
ifeq ($(PX4_TARGET_OS),posix)
|
||||
include $(PX4_BASE)makefiles/firmware_posix.mk
|
||||
endif
|
||||
ifeq ($(PX4_TARGET_OS),qurt)
|
||||
include $(PX4_BASE)makefiles/firmware_qurt.mk
|
||||
endif
|
||||
|
||||
|
||||
.PHONY: checksubmodules
|
||||
checksubmodules:
|
||||
$(Q) ($(PX4_BASE)/Tools/check_submodules.sh)
|
||||
@@ -229,7 +245,7 @@ MSG_DIR = $(PX4_BASE)msg
|
||||
UORB_TEMPLATE_DIR = $(PX4_BASE)msg/templates/uorb
|
||||
MULTIPLATFORM_TEMPLATE_DIR = $(PX4_BASE)msg/templates/px4/uorb
|
||||
TOPICS_DIR = $(PX4_BASE)src/modules/uORB/topics
|
||||
MULTIPLATFORM_HEADER_DIR = $(PX4_BASE)src/platforms/nuttx/px4_messages
|
||||
MULTIPLATFORM_HEADER_DIR = $(PX4_BASE)src/platforms/$(PX4_TARGET_OS)/px4_messages
|
||||
MULTIPLATFORM_PREFIX = px4_
|
||||
TOPICHEADER_TEMP_DIR = $(BUILD_DIR)topics_temporary
|
||||
GENMSG_PYTHONPATH = $(PX4_BASE)Tools/genmsg/src
|
||||
@@ -255,6 +271,21 @@ testbuild:
|
||||
$(Q) (cd $(PX4_BASE) && $(MAKE) distclean && $(MAKE) archives && $(MAKE) -j8)
|
||||
$(Q) (zip -r Firmware.zip $(PX4_BASE)/Images)
|
||||
|
||||
posix:
|
||||
make PX4_TARGET_OS=posix
|
||||
|
||||
nuttx:
|
||||
make PX4_TARGET_OS=nuttx
|
||||
|
||||
qurt:
|
||||
make PX4_TARGET_OS=qurt
|
||||
|
||||
posixrun:
|
||||
Tools/posix_run.sh
|
||||
|
||||
qurtrun:
|
||||
make PX4_TARGET_OS=qurt sim
|
||||
|
||||
#
|
||||
# Unittest targets. Builds and runs the host-level
|
||||
# unit tests.
|
||||
|
||||
Executable
+150
@@ -0,0 +1,150 @@
|
||||
#!/usr/bin/python
|
||||
|
||||
import glob
|
||||
import sys
|
||||
|
||||
# This script is run from Build/<target>_default.build/$(PX4_BASE)/Firmware/src/systemcmds/topic_listener
|
||||
|
||||
# argv[1] must be the full path of the top Firmware dir
|
||||
|
||||
raw_messages = glob.glob(sys.argv[1]+"/msg/*.msg")
|
||||
messages = []
|
||||
message_elements = []
|
||||
|
||||
|
||||
for index,m in enumerate(raw_messages):
|
||||
temp_list_floats = []
|
||||
temp_list_uint64 = []
|
||||
temp_list_bool = []
|
||||
if("actuator_control" not in m and "pwm_input" not in m and "position_setpoint" not in m):
|
||||
temp_list = []
|
||||
f = open(m,'r')
|
||||
for line in f.readlines():
|
||||
if(line.split(' ')[0] == "float32"):
|
||||
temp_list.append(("float",line.split(' ')[1].split('\t')[0].split('\n')[0]))
|
||||
elif(line.split(' ')[0] == "uint64"):
|
||||
temp_list.append(("uint64",line.split(' ')[1].split('\t')[0].split('\n')[0]))
|
||||
elif (line.split(' ')[0] == "bool"):
|
||||
temp_list.append(("bool",line.split(' ')[1].split('\t')[0].split('\n')[0]))
|
||||
elif (line.split(' ')[0] == "uint8") and len(line.split('=')) == 1:
|
||||
temp_list.append(("uint8",line.split(' ')[1].split('\t')[0].split('\n')[0]))
|
||||
elif ('float32[' in line.split(' ')[0]):
|
||||
num_floats = int(line.split(" ")[0].split("[")[1].split("]")[0])
|
||||
temp_list.append(("float_array",line.split(' ')[1].split('\t')[0].split('\n')[0],num_floats))
|
||||
|
||||
f.close()
|
||||
messages.append(m.split('/')[-1].split('.')[0])
|
||||
message_elements.append(temp_list)
|
||||
|
||||
num_messages = len(messages);
|
||||
|
||||
print
|
||||
print """
|
||||
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2015 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 topic_listener.cpp, autogenerated by Tools/generate_listener.py
|
||||
*
|
||||
* Tool for listening to topics when running flight stack on linux.
|
||||
*/
|
||||
#include <px4_middleware.h>
|
||||
#include <px4_app.h>
|
||||
#include <px4_config.h>
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include <string>
|
||||
#include <sstream>
|
||||
#include <vector>
|
||||
#include <cstring>
|
||||
#include <uORB/uORB.h>
|
||||
#include <string.h>
|
||||
#include <stdint.h>
|
||||
"""
|
||||
for m in messages:
|
||||
print "#include <uORB/topics/%s.h>" % m
|
||||
|
||||
|
||||
print """
|
||||
extern "C" __EXPORT int listener_main(int argc, char *argv[]);
|
||||
|
||||
int listener_main(int argc, char *argv[]) {
|
||||
int sub = -1;
|
||||
orb_id_t ID;
|
||||
if(argc < 3) {
|
||||
printf("need at least two arguments: topic name, number of messages to print\\n");
|
||||
return 1;
|
||||
}
|
||||
"""
|
||||
print "\tuint32_t num_msgs = (uint32_t)std::stoi(argv[2],NULL,10);"
|
||||
print "\tif(strncmp(argv[1],\"%s\",50)== 0) {" % messages[0]
|
||||
print "\t\tsub = orb_subscribe(ORB_ID(%s));" % messages[0]
|
||||
print "\t\tID = ORB_ID(%s);" % messages[0]
|
||||
print "\t\tstruct %s_s container;" % messages[0]
|
||||
print "\t\tmemset(&container, 0, sizeof(container));"
|
||||
for index,m in enumerate(messages[1:]):
|
||||
print "\t} else if(strncmp(argv[1],\"%s\",50) == 0) {" % m
|
||||
print "\t\tsub = orb_subscribe(ORB_ID(%s));" % m
|
||||
print "\t\tID = ORB_ID(%s);" % m
|
||||
print "\t\tstruct %s_s container;" % m
|
||||
print "\t\tmemset(&container, 0, sizeof(container));"
|
||||
print "\t\tbool updated;"
|
||||
print "\t\tfor(uint32_t i = 0;i<num_msgs;i++) {"
|
||||
print "\t\t\torb_check(sub,&updated);"
|
||||
print "\t\t\tupdated = true;"
|
||||
print "\t\t\tif(updated) {"
|
||||
print "\t\t\torb_copy(ID,sub,&container);"
|
||||
for item in message_elements[index+1]:
|
||||
if item[0] == "float":
|
||||
print "\t\t\tprintf(\"%s: %%f\\n \",(double)container.%s);" % (item[1], item[1])
|
||||
elif item[0] == "float_array":
|
||||
print "\t\t\tprintf(\"%s:\");" % item[1]
|
||||
print "\t\t\tfor (int j=0;j<%d;j++) {" % item[2]
|
||||
print "\t\t\t\tprintf(\"%%f \",(double)container.%s[j]);" % item[1]
|
||||
print "\t\t\t}"
|
||||
print "\t\t\tprintf(\"\\n\");"
|
||||
elif item[0] == "uint64":
|
||||
print "\t\t\tprintf(\"%s: %%lu\\n \",container.%s);" % (item[1], item[1])
|
||||
elif item[0] == "uint8":
|
||||
print "\t\t\tprintf(\"%s: %%u\\n \",container.%s);" % (item[1], item[1])
|
||||
elif item[0] == "bool":
|
||||
print "\t\t\tprintf(\"%s: %%s\\n \",container.%s ? \"True\" : \"False\");" % (item[1], item[1])
|
||||
print "\t\t\t}"
|
||||
print "\t\t}"
|
||||
print "\t} else {"
|
||||
print "\t\t printf(\" Topic did not match any known topics\\n\");"
|
||||
print "\t}"
|
||||
print("\t return 0;")
|
||||
|
||||
print "}"
|
||||
Executable
+126
@@ -0,0 +1,126 @@
|
||||
#!/usr/bin/env python
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2015 Mark Charlebois. 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
import glob
|
||||
builtins = glob.glob("builtin_commands/COMMAND*")
|
||||
|
||||
apps = []
|
||||
for f in builtins:
|
||||
apps.append(f.split(".")[-1].split("_main")[0])
|
||||
|
||||
print
|
||||
print """
|
||||
#include <string>
|
||||
#include <map>
|
||||
|
||||
#define __EXPORT
|
||||
|
||||
#include <px4_tasks.h>
|
||||
#include <px4_posix.h>
|
||||
|
||||
using namespace std;
|
||||
|
||||
extern void px4_show_devices(void);
|
||||
|
||||
extern "C" {
|
||||
"""
|
||||
for app in apps:
|
||||
print "extern int "+app+"_main(int argc, char *argv[]);"
|
||||
|
||||
print """
|
||||
static int shutdown_main(int argc, char *argv[]);
|
||||
static int list_tasks_main(int argc, char *argv[]);
|
||||
static int list_files_main(int argc, char *argv[]);
|
||||
static int list_devices_main(int argc, char *argv[]);
|
||||
static int list_topics_main(int argc, char *argv[]);
|
||||
}
|
||||
|
||||
|
||||
static map<string,px4_main_t> app_map(void);
|
||||
|
||||
static map<string,px4_main_t> app_map(void)
|
||||
{
|
||||
static map<string,px4_main_t> apps;
|
||||
"""
|
||||
for app in apps:
|
||||
print '\tapps["'+app+'"] = '+app+'_main;'
|
||||
|
||||
print '\tapps["shutdown"] = shutdown_main;'
|
||||
print '\tapps["list_tasks"] = list_tasks_main;'
|
||||
print '\tapps["list_files"] = list_files_main;'
|
||||
print '\tapps["list_devices"] = list_devices_main;'
|
||||
print '\tapps["list_topics"] = list_topics_main;'
|
||||
print """
|
||||
return apps;
|
||||
}
|
||||
|
||||
map<string,px4_main_t> apps = app_map();
|
||||
|
||||
static void list_builtins(void)
|
||||
{
|
||||
cout << "Builtin Commands:" << endl;
|
||||
for (map<string,px4_main_t>::iterator it=apps.begin(); it!=apps.end(); ++it)
|
||||
cout << '\t' << it->first << endl;
|
||||
}
|
||||
|
||||
static int shutdown_main(int argc, char *argv[])
|
||||
{
|
||||
cout << "Shutting down" << endl;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
static int list_tasks_main(int argc, char *argv[])
|
||||
{
|
||||
px4_show_tasks();
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int list_devices_main(int argc, char *argv[])
|
||||
{
|
||||
px4_show_devices();
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int list_topics_main(int argc, char *argv[])
|
||||
{
|
||||
px4_show_topics();
|
||||
return 0;
|
||||
}
|
||||
static int list_files_main(int argc, char *argv[])
|
||||
{
|
||||
px4_show_files();
|
||||
return 0;
|
||||
}
|
||||
"""
|
||||
|
||||
Executable
+19
@@ -0,0 +1,19 @@
|
||||
#!/bin/bash
|
||||
|
||||
if [ ! -d /fs/msdcard ] && [ ! -w /fs/msdcard ]
|
||||
then
|
||||
echo "Need to create/mount writable /fs/microsd"
|
||||
echo "sudo mkdir -p /fs/msdcard"
|
||||
echo "sudo chmod 777 /fs/msdcard"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
if [ ! -d /eeprom ] && [ ! -w /eeprom ]
|
||||
then
|
||||
echo "Need to create/mount writable /eeprom"
|
||||
echo "sudo mkdir -p /eeprom"
|
||||
echo "sudo chmod 777 /eeprom"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
Build/posix_default.build/mainapp posix-configs/posixtest/init/rc.S
|
||||
Executable
+121
@@ -0,0 +1,121 @@
|
||||
#!/usr/bin/env python
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2015 Mark Charlebois. 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
import glob
|
||||
#builtins = glob.glob("../Build/linux_default.build/builtin_commands/COMMAND*")
|
||||
builtins = glob.glob("builtin_commands/COMMAND*")
|
||||
|
||||
apps = []
|
||||
for f in builtins:
|
||||
apps.append(f.split(".")[-1].split("_main")[0])
|
||||
|
||||
print
|
||||
print """
|
||||
#include <string>
|
||||
#include <map>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <px4_tasks.h>
|
||||
#include <px4_posix.h>
|
||||
|
||||
using namespace std;
|
||||
|
||||
extern void px4_show_devices(void);
|
||||
|
||||
extern "C" {
|
||||
"""
|
||||
for app in apps:
|
||||
print "extern int "+app+"_main(int argc, char *argv[]);"
|
||||
|
||||
print """
|
||||
static int shutdown_main(int argc, char *argv[]);
|
||||
static int list_tasks_main(int argc, char *argv[]);
|
||||
static int list_files_main(int argc, char *argv[]);
|
||||
static int list_devices_main(int argc, char *argv[]);
|
||||
static int list_topics_main(int argc, char *argv[]);
|
||||
}
|
||||
|
||||
|
||||
void init_app_map(map<string,px4_main_t> &apps)
|
||||
{
|
||||
"""
|
||||
for app in apps:
|
||||
print '\tapps["'+app+'"] = '+app+'_main;'
|
||||
|
||||
print '\tapps["shutdown"] = shutdown_main;'
|
||||
print '\tapps["list_tasks"] = list_tasks_main;'
|
||||
print '\tapps["list_files"] = list_files_main;'
|
||||
print '\tapps["list_devices"] = list_devices_main;'
|
||||
print '\tapps["list_topics"] = list_topics_main;'
|
||||
|
||||
print """
|
||||
}
|
||||
|
||||
void list_builtins(map<string,px4_main_t> &apps)
|
||||
{
|
||||
printf("Builtin Commands:\\n");
|
||||
for (map<string,px4_main_t>::iterator it=apps.begin(); it!=apps.end(); ++it)
|
||||
printf("\\t%s\\n", (it->first).c_str());
|
||||
}
|
||||
|
||||
static int shutdown_main(int argc, char *argv[])
|
||||
{
|
||||
printf("Shutting down\\n");
|
||||
exit(0);
|
||||
}
|
||||
|
||||
static int list_tasks_main(int argc, char *argv[])
|
||||
{
|
||||
px4_show_tasks();
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int list_devices_main(int argc, char *argv[])
|
||||
{
|
||||
px4_show_devices();
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int list_topics_main(int argc, char *argv[])
|
||||
{
|
||||
px4_show_topics();
|
||||
return 0;
|
||||
}
|
||||
static int list_files_main(int argc, char *argv[])
|
||||
{
|
||||
px4_show_files();
|
||||
return 0;
|
||||
}
|
||||
"""
|
||||
|
||||
+23
-8
@@ -7,8 +7,9 @@ with Makefile in the parent directory.
|
||||
|
||||
../Makefile
|
||||
|
||||
Top-level makefile for the PX4 build system. This makefile supports
|
||||
building NuttX archives, as well as supervising the building of all
|
||||
Top-level makefile for the PX4 build system.
|
||||
This makefile supports building NuttX archives for the NuttX based
|
||||
configurations, as well as supervising the building of all
|
||||
of the defined PX4 firmware configurations.
|
||||
|
||||
Try 'make help' in the parent directory for documentation.
|
||||
@@ -25,6 +26,14 @@ firmware.mk
|
||||
source tree. When used in this mode, at least BOARD, MODULES and
|
||||
CONFIG_FILE must be set.
|
||||
|
||||
firmware_nuttx.mk
|
||||
|
||||
Called by firmware.mk to build NuttX based firmware.
|
||||
|
||||
firmware_posix.mk
|
||||
|
||||
Called by firmware.mk to build POSIX (non-ROS) based firmware.
|
||||
|
||||
module.mk
|
||||
|
||||
Called by firmware.mk to build individual modules.
|
||||
@@ -34,22 +43,28 @@ module.mk
|
||||
|
||||
nuttx.mk
|
||||
|
||||
Called by ../Makefile to build or download the NuttX archives.
|
||||
Called by ../Makefile to build or download the NuttX archives if
|
||||
PX4_TARGET_OS is set to "nuttx".
|
||||
|
||||
posix.mk
|
||||
|
||||
Called by ../Makefile to set POSIX specific parameters if
|
||||
PX4_TARGET_OS is set to "posix".
|
||||
|
||||
upload.mk
|
||||
|
||||
Called by ../Makefile to upload files to a target board. Can be used
|
||||
by external build systems as well.
|
||||
by external build systems as well. (NuttX targets only)
|
||||
|
||||
setup.mk
|
||||
|
||||
Provides common path and tool definitions. Implements host system-specific
|
||||
compatibility hacks.
|
||||
Provides common path and tool definitions. Implements host
|
||||
system-specific compatibility hacks. Sets PX4_TARGET_OS.
|
||||
|
||||
board_<boardname>.mk
|
||||
|
||||
Board-specific configuration for <boardname>. Typically sets CONFIG_ARCH
|
||||
and then includes the toolchain definition for the board.
|
||||
Board-specific configuration for <boardname>. Typically sets
|
||||
CONFIG_ARCH and then includes the toolchain definition for the board.
|
||||
|
||||
config_<boardname>_<configname>.mk
|
||||
|
||||
|
||||
+26
-6
@@ -132,7 +132,7 @@ include $(MK_DIR)/setup.mk
|
||||
ifneq ($(CONFIG_FILE),)
|
||||
CONFIG := $(subst config_,,$(basename $(notdir $(CONFIG_FILE))))
|
||||
else
|
||||
CONFIG_FILE := $(wildcard $(PX4_MK_DIR)/config_$(CONFIG).mk)
|
||||
CONFIG_FILE := $(wildcard $(PX4_MK_DIR)/$(PX4_TARGET_OS)/config_$(CONFIG).mk)
|
||||
endif
|
||||
ifeq ($(CONFIG),)
|
||||
$(error Missing configuration name or file (specify with CONFIG=<config>))
|
||||
@@ -150,7 +150,7 @@ $(info % CONFIG = $(CONFIG))
|
||||
ifeq ($(BOARD),)
|
||||
BOARD := $(firstword $(subst _, ,$(CONFIG)))
|
||||
endif
|
||||
BOARD_FILE := $(wildcard $(PX4_MK_DIR)/board_$(BOARD).mk)
|
||||
BOARD_FILE := $(wildcard $(PX4_MK_DIR)/$(PX4_TARGET_OS)/board_$(BOARD).mk)
|
||||
ifeq ($(BOARD_FILE),)
|
||||
$(error Config $(CONFIG) references board $(BOARD), but no board definition file found)
|
||||
endif
|
||||
@@ -186,10 +186,10 @@ EXTRA_CLEANS =
|
||||
INCLUDE_DIRS += $(PX4_MODULE_SRC)drivers/boards/$(BOARD)
|
||||
|
||||
################################################################################
|
||||
# NuttX libraries and paths
|
||||
# OS specific libraries and paths
|
||||
################################################################################
|
||||
|
||||
include $(PX4_MK_DIR)/nuttx.mk
|
||||
include $(PX4_MK_DIR)/$(PX4_TARGET_OS).mk
|
||||
|
||||
################################################################################
|
||||
# Modules
|
||||
@@ -213,7 +213,7 @@ endef
|
||||
MODULE_MKFILES := $(foreach module,$(MODULES),$(call MODULE_SEARCH,$(module)))
|
||||
MISSING_MODULES := $(subst MISSING_,,$(filter MISSING_%,$(MODULE_MKFILES)))
|
||||
ifneq ($(MISSING_MODULES),)
|
||||
$(error Can't find module(s): $(MISSING_MODULES))
|
||||
$(error Cant find module(s): $(MISSING_MODULES))
|
||||
endif
|
||||
|
||||
# Make a list of the object files we expect to build from modules
|
||||
@@ -273,7 +273,7 @@ endef
|
||||
LIBRARY_MKFILES := $(foreach library,$(LIBRARIES),$(call LIBRARY_SEARCH,$(library)))
|
||||
MISSING_LIBRARIES := $(subst MISSING_,,$(filter MISSING_%,$(LIBRARY_MKFILES)))
|
||||
ifneq ($(MISSING_LIBRARIES),)
|
||||
$(error Can't find library(s): $(MISSING_LIBRARIES))
|
||||
$(error Cant find library(s): $(MISSING_LIBRARIES))
|
||||
endif
|
||||
|
||||
# Make a list of the archive files we expect to build from libraries
|
||||
@@ -311,6 +311,7 @@ $(LIBRARY_CLEANS):
|
||||
LIBRARY_MK=$(mkfile) \
|
||||
clean
|
||||
|
||||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
################################################################################
|
||||
# ROMFS generation
|
||||
################################################################################
|
||||
@@ -434,6 +435,7 @@ SRCS += $(BUILTIN_CSRC)
|
||||
|
||||
EXTRA_CLEANS += $(BUILTIN_CSRC)
|
||||
|
||||
endif
|
||||
endif
|
||||
|
||||
################################################################################
|
||||
@@ -456,6 +458,7 @@ endif
|
||||
# Build rules
|
||||
################################################################################
|
||||
|
||||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
#
|
||||
# What we're going to build.
|
||||
#
|
||||
@@ -466,6 +469,7 @@ PRODUCT_PARAMXML = $(WORK_DIR)/parameters.xml
|
||||
|
||||
.PHONY: firmware
|
||||
firmware: $(PRODUCT_BUNDLE)
|
||||
endif
|
||||
|
||||
#
|
||||
# Object files we will generate from sources
|
||||
@@ -487,6 +491,7 @@ $(filter %.cpp.o,$(OBJS)): $(WORK_DIR)%.cpp.o: %.cpp $(GLOBAL_DEPS)
|
||||
$(filter %.S.o,$(OBJS)): $(WORK_DIR)%.S.o: %.S $(GLOBAL_DEPS)
|
||||
$(call ASSEMBLE,$<,$@)
|
||||
|
||||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
#
|
||||
# Built product rules
|
||||
#
|
||||
@@ -530,7 +535,22 @@ clean: $(MODULE_CLEANS)
|
||||
$(Q) $(REMOVE) $(PRODUCT_BUNDLE) $(PRODUCT_BIN) $(PRODUCT_ELF)
|
||||
$(Q) $(REMOVE) $(OBJS) $(DEP_INCLUDES) $(EXTRA_CLEANS)
|
||||
$(Q) $(RMDIR) $(NUTTX_EXPORT_DIR)
|
||||
endif
|
||||
|
||||
# Include the OS specific build rules
|
||||
# The rules must define the "firmware" make target
|
||||
#
|
||||
|
||||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
# TODO
|
||||
# Move above nuttx specific rules to $(MK_DIR)/nuttx_romfs.mk
|
||||
endif
|
||||
ifeq ($(PX4_TARGET_OS),posix)
|
||||
include $(MK_DIR)/posix_elf.mk
|
||||
endif
|
||||
ifeq ($(PX4_TARGET_OS),qurt)
|
||||
include $(MK_DIR)/qurt_elf.mk
|
||||
endif
|
||||
|
||||
#
|
||||
# DEP_INCLUDES is defined by the toolchain include in terms of $(OBJS)
|
||||
|
||||
@@ -0,0 +1,151 @@
|
||||
#
|
||||
# Copyright (c) 2012-2015 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.
|
||||
#
|
||||
|
||||
#
|
||||
# Built products
|
||||
#
|
||||
|
||||
DESIRED_FIRMWARES = $(foreach config,$(CONFIGS),$(IMAGE_DIR)$(config).px4)
|
||||
STAGED_FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(IMAGE_DIR)$(config).px4)
|
||||
FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(BUILD_DIR)$(config).build/firmware.px4)
|
||||
|
||||
all: $(DESIRED_FIRMWARES)
|
||||
|
||||
#
|
||||
# Copy FIRMWARES into the image directory.
|
||||
#
|
||||
# XXX copying the .bin files is a hack to work around the PX4IO uploader
|
||||
# not supporting .px4 files, and it should be deprecated onced that
|
||||
# is taken care of.
|
||||
#
|
||||
$(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4
|
||||
@$(ECHO) %% Copying $@
|
||||
$(Q) $(COPY) $< $@
|
||||
$(Q) $(COPY) $(patsubst %.px4,%.bin,$<) $(patsubst %.px4,%.bin,$@)
|
||||
|
||||
#
|
||||
# Generate FIRMWARES.
|
||||
#
|
||||
.PHONY: $(FIRMWARES)
|
||||
$(BUILD_DIR)%.build/firmware.px4: config = $(patsubst $(BUILD_DIR)%.build/firmware.px4,%,$@)
|
||||
$(BUILD_DIR)%.build/firmware.px4: work_dir = $(BUILD_DIR)$(config).build/
|
||||
$(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4: generateuorbtopicheaders checksubmodules
|
||||
@$(ECHO) %%%%
|
||||
@$(ECHO) %%%% Building $(config) in $(work_dir)
|
||||
@$(ECHO) %%%%
|
||||
$(Q) $(MKDIR) -p $(work_dir)
|
||||
$(Q) $(MAKE) -r -C $(work_dir) \
|
||||
-f $(PX4_MK_DIR)firmware.mk \
|
||||
CONFIG=$(config) \
|
||||
WORK_DIR=$(work_dir) \
|
||||
$(FIRMWARE_GOAL)
|
||||
|
||||
#
|
||||
# Make FMU firmwares depend on the corresponding IO firmware.
|
||||
#
|
||||
# This is a pretty vile hack, since it hard-codes knowledge of the FMU->IO dependency
|
||||
# and forces the _default config in all cases. There has to be a better way to do this...
|
||||
#
|
||||
FMU_VERSION = $(patsubst px4fmu-%,%,$(word 1, $(subst _, ,$(1))))
|
||||
define FMU_DEP
|
||||
$(BUILD_DIR)$(1).build/firmware.px4: $(IMAGE_DIR)px4io-$(call FMU_VERSION,$(1))_default.px4
|
||||
endef
|
||||
FMU_CONFIGS := $(filter px4fmu%,$(CONFIGS))
|
||||
$(foreach config,$(FMU_CONFIGS),$(eval $(call FMU_DEP,$(config))))
|
||||
|
||||
#
|
||||
# Build the NuttX export archives.
|
||||
#
|
||||
# Note that there are no explicit dependencies extended from these
|
||||
# archives. If NuttX is updated, the user is expected to rebuild the
|
||||
# archives/build area manually. Likewise, when the 'archives' target is
|
||||
# invoked, all archives are always rebuilt.
|
||||
#
|
||||
# XXX Should support fetching/unpacking from a separate directory to permit
|
||||
# downloads of the prebuilt archives as well...
|
||||
#
|
||||
NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export)
|
||||
.PHONY: archives
|
||||
archives: checksubmodules $(NUTTX_ARCHIVES)
|
||||
|
||||
# We cannot build these parallel; note that we also force -j1 for the
|
||||
# sub-make invocations.
|
||||
ifneq ($(filter archives,$(MAKECMDGOALS)),)
|
||||
.NOTPARALLEL:
|
||||
endif
|
||||
|
||||
J?=1
|
||||
|
||||
$(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@))
|
||||
$(ARCHIVE_DIR)%.export: configuration = nsh
|
||||
$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC)
|
||||
@$(ECHO) %% Configuring NuttX for $(board)
|
||||
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
|
||||
$(Q) $(MAKE) -r -j$(J) -C $(NUTTX_SRC) -r $(MQUIET) distclean
|
||||
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .)
|
||||
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
|
||||
@$(ECHO) %% Exporting NuttX for $(board)
|
||||
$(Q) $(MAKE) -r -j$(J) -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export
|
||||
$(Q) $(MKDIR) -p $(dir $@)
|
||||
$(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
|
||||
$(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board))
|
||||
|
||||
#
|
||||
# The user can run the NuttX 'menuconfig' tool for a single board configuration with
|
||||
# make BOARDS=<boardname> menuconfig
|
||||
#
|
||||
ifeq ($(MAKECMDGOALS),menuconfig)
|
||||
ifneq ($(words $(BOARDS)),1)
|
||||
$(error BOARDS must specify exactly one board for the menuconfig goal)
|
||||
endif
|
||||
BOARD = $(BOARDS)
|
||||
menuconfig: $(NUTTX_SRC)
|
||||
@$(ECHO) %% Configuring NuttX for $(BOARD)
|
||||
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
|
||||
$(Q) $(MAKE) -r -j$(J) -C $(NUTTX_SRC) -r $(MQUIET) distclean
|
||||
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(BOARD) .)
|
||||
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(BOARD)/nsh)
|
||||
@$(ECHO) %% Running menuconfig for $(BOARD)
|
||||
$(Q) $(MAKE) -r -j$(J) -C $(NUTTX_SRC) -r $(MQUIET) menuconfig
|
||||
@$(ECHO) %% Saving configuration file
|
||||
$(Q)$(COPY) $(NUTTX_SRC).config $(PX4_BASE)nuttx-configs/$(BOARD)/nsh/defconfig
|
||||
else
|
||||
menuconfig:
|
||||
@$(ECHO) ""
|
||||
@$(ECHO) "The menuconfig goal must be invoked without any other goal being specified"
|
||||
@$(ECHO) ""
|
||||
endif
|
||||
|
||||
$(NUTTX_SRC): checksubmodules
|
||||
|
||||
$(UAVCAN_DIR):
|
||||
$(Q) (./Tools/check_submodules.sh)
|
||||
|
||||
@@ -0,0 +1,56 @@
|
||||
#
|
||||
# Copyright (c) 2012-2015 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.
|
||||
#
|
||||
|
||||
#
|
||||
# Built products
|
||||
#
|
||||
FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(BUILD_DIR)$(config).build/firmware.a)
|
||||
|
||||
all: $(FIRMWARES)
|
||||
|
||||
#
|
||||
# Generate FIRMWARES.
|
||||
#
|
||||
.PHONY: $(FIRMWARES)
|
||||
$(BUILD_DIR)%.build/firmware.a: config = $(patsubst $(BUILD_DIR)%.build/firmware.a,%,$@)
|
||||
$(BUILD_DIR)%.build/firmware.a: work_dir = $(BUILD_DIR)$(config).build/
|
||||
$(FIRMWARES): $(BUILD_DIR)%.build/firmware.a: generateuorbtopicheaders
|
||||
@$(ECHO) %%%%
|
||||
@$(ECHO) %%%% Building $(config) in $(work_dir)
|
||||
@$(ECHO) %%%%
|
||||
$(Q) $(MKDIR) -p $(work_dir)
|
||||
$(Q) $(MAKE) -r -C $(work_dir) \
|
||||
-f $(PX4_MK_DIR)firmware.mk \
|
||||
CONFIG=$(config) \
|
||||
WORK_DIR=$(work_dir) \
|
||||
$(FIRMWARE_GOAL)
|
||||
|
||||
|
||||
@@ -0,0 +1,63 @@
|
||||
#
|
||||
# Copyright (c) 2012-2015 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.
|
||||
#
|
||||
|
||||
#
|
||||
# Built products
|
||||
#
|
||||
FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(BUILD_DIR)$(config).build/firmware.a)
|
||||
|
||||
all: $(FIRMWARES)
|
||||
|
||||
#
|
||||
# Generate FIRMWARES.
|
||||
#
|
||||
.PHONY: $(FIRMWARES)
|
||||
$(BUILD_DIR)%.build/firmware.a: config = $(patsubst $(BUILD_DIR)%.build/firmware.a,%,$@)
|
||||
$(BUILD_DIR)%.build/firmware.a: work_dir = $(BUILD_DIR)$(config).build/
|
||||
$(FIRMWARES): $(BUILD_DIR)%.build/firmware.a: generateuorbtopicheaders
|
||||
@$(ECHO) %%%%
|
||||
@$(ECHO) %%%% Building $(config) in $(work_dir)
|
||||
@$(ECHO) %%%%
|
||||
$(Q) $(MKDIR) -p $(work_dir)
|
||||
$(Q) $(MAKE) -r -C $(work_dir) \
|
||||
-f $(PX4_MK_DIR)firmware.mk \
|
||||
CONFIG=$(config) \
|
||||
WORK_DIR=$(work_dir) \
|
||||
$(FIRMWARE_GOAL)
|
||||
|
||||
HEXAGON_TOOLS_ROOT = /opt/6.4.05
|
||||
#V_ARCH = v4
|
||||
V_ARCH = v5
|
||||
HEXAGON_CLANG_BIN = $(addsuffix /qc/bin,$(HEXAGON_TOOLS_ROOT))
|
||||
SIM = $(HEXAGON_CLANG_BIN)/hexagon-sim
|
||||
SIMFLAGS+= -m$(V_ARCH)
|
||||
sim:
|
||||
$(SIM) $(SIMFLAGS) Build/qurt_default.build/mainapp
|
||||
@@ -93,7 +93,7 @@ $(info %% LIBRARY_MK = $(LIBRARY_MK))
|
||||
#
|
||||
# Get the board/toolchain config
|
||||
#
|
||||
include $(PX4_MK_DIR)/board_$(BOARD).mk
|
||||
include $(PX4_MK_DIR)/$(PX4_TARGET_OS)/board_$(BOARD).mk
|
||||
|
||||
#
|
||||
# Get the library's config
|
||||
|
||||
@@ -144,6 +144,7 @@ MODULE_ENTRYPOINT ?= $(MODULE_COMMAND)_main
|
||||
MODULE_STACKSIZE ?= CONFIG_PTHREAD_STACK_DEFAULT
|
||||
MODULE_PRIORITY ?= SCHED_PRIORITY_DEFAULT
|
||||
MODULE_COMMANDS += $(MODULE_COMMAND).$(MODULE_PRIORITY).$(MODULE_STACKSIZE).$(MODULE_ENTRYPOINT)
|
||||
CXXFLAGS += -DPX4_MAIN=$(MODULE_COMMAND)_app_main
|
||||
endif
|
||||
|
||||
ifneq ($(MODULE_COMMANDS),)
|
||||
|
||||
@@ -34,6 +34,8 @@
|
||||
# building firmware.
|
||||
#
|
||||
|
||||
MODULES += platforms/nuttx/px4_layer platforms/common
|
||||
|
||||
#
|
||||
# Check that the NuttX archive for the selected board is available.
|
||||
#
|
||||
|
||||
@@ -0,0 +1,219 @@
|
||||
#
|
||||
# Copyright (C) 2012 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.
|
||||
#
|
||||
|
||||
#
|
||||
# Makefile for PX4 Nuttx based firmware images.
|
||||
#
|
||||
|
||||
################################################################################
|
||||
# ROMFS generation
|
||||
################################################################################
|
||||
|
||||
ifneq ($(ROMFS_ROOT),)
|
||||
ifeq ($(wildcard $(ROMFS_ROOT)),)
|
||||
$(error ROMFS_ROOT specifies a directory that does not exist)
|
||||
endif
|
||||
|
||||
#
|
||||
# Note that there is no support for more than one root directory or constructing
|
||||
# a root from several templates. That would be a nice feature.
|
||||
#
|
||||
|
||||
# Add dependencies on anything in the ROMFS root directory
|
||||
ROMFS_FILES += $(wildcard \
|
||||
$(ROMFS_ROOT)/* \
|
||||
$(ROMFS_ROOT)/*/* \
|
||||
$(ROMFS_ROOT)/*/*/* \
|
||||
$(ROMFS_ROOT)/*/*/*/* \
|
||||
$(ROMFS_ROOT)/*/*/*/*/* \
|
||||
$(ROMFS_ROOT)/*/*/*/*/*/*)
|
||||
ifeq ($(ROMFS_FILES),)
|
||||
$(error ROMFS_ROOT $(ROMFS_ROOT) specifies a directory containing no files)
|
||||
endif
|
||||
ROMFS_DEPS += $(ROMFS_FILES)
|
||||
|
||||
# Extra files that may be copied into the ROMFS /extras directory
|
||||
# ROMFS_EXTRA_FILES are required, ROMFS_OPTIONAL_FILES are optional
|
||||
ROMFS_EXTRA_FILES += $(wildcard $(ROMFS_OPTIONAL_FILES))
|
||||
ROMFS_DEPS += $(ROMFS_EXTRA_FILES)
|
||||
|
||||
ROMFS_IMG = romfs.img
|
||||
ROMFS_SCRATCH = romfs_scratch
|
||||
ROMFS_CSRC = $(ROMFS_IMG:.img=.c)
|
||||
ROMFS_OBJ = $(ROMFS_CSRC:.c=.o)
|
||||
LIBS += $(ROMFS_OBJ)
|
||||
LINK_DEPS += $(ROMFS_OBJ)
|
||||
|
||||
# Remove all comments from startup and mixer files
|
||||
ROMFS_PRUNER = $(PX4_BASE)/Tools/px_romfs_pruner.py
|
||||
|
||||
# Turn the ROMFS image into an object file
|
||||
$(ROMFS_OBJ): $(ROMFS_IMG) $(GLOBAL_DEPS)
|
||||
$(call BIN_TO_OBJ,$<,$@,romfs_img)
|
||||
|
||||
# Generate the ROMFS image from the root
|
||||
$(ROMFS_IMG): $(ROMFS_SCRATCH) $(ROMFS_DEPS) $(GLOBAL_DEPS)
|
||||
@$(ECHO) "ROMFS: $@"
|
||||
$(Q) $(GENROMFS) -f $@ -d $(ROMFS_SCRATCH) -V "NSHInitVol"
|
||||
|
||||
# Construct the ROMFS scratch root from the canonical root
|
||||
$(ROMFS_SCRATCH): $(ROMFS_DEPS) $(GLOBAL_DEPS)
|
||||
$(Q) $(MKDIR) -p $(ROMFS_SCRATCH)
|
||||
$(Q) $(COPYDIR) $(ROMFS_ROOT)/* $(ROMFS_SCRATCH)
|
||||
# delete all files in ROMFS_SCRATCH which start with a . or end with a ~
|
||||
$(Q) $(RM) $(ROMFS_SCRATCH)/*/.[!.]* $(ROMFS_SCRATCH)/*/*~
|
||||
ifneq ($(ROMFS_EXTRA_FILES),)
|
||||
$(Q) $(MKDIR) -p $(ROMFS_SCRATCH)/extras
|
||||
$(Q) $(COPY) $(ROMFS_EXTRA_FILES) $(ROMFS_SCRATCH)/extras
|
||||
endif
|
||||
$(Q) $(PYTHON) -u $(ROMFS_PRUNER) --folder $(ROMFS_SCRATCH)
|
||||
|
||||
EXTRA_CLEANS += $(ROMGS_OBJ) $(ROMFS_IMG)
|
||||
|
||||
endif
|
||||
|
||||
################################################################################
|
||||
# Builtin command list generation
|
||||
################################################################################
|
||||
|
||||
#
|
||||
# Builtin commands can be generated by the configuration, in which case they
|
||||
# must refer to commands that already exist, or indirectly generated by modules
|
||||
# when they are built.
|
||||
#
|
||||
# The configuration supplies builtin command information in the BUILTIN_COMMANDS
|
||||
# variable. Applications make empty files in $(WORK_DIR)/builtin_commands whose
|
||||
# filename contains the same information.
|
||||
#
|
||||
# In each case, the command information consists of four fields separated with a
|
||||
# period. These fields are the command's name, its thread priority, its stack size
|
||||
# and the name of the function to call when starting the thread.
|
||||
#
|
||||
BUILTIN_CSRC = $(WORK_DIR)builtin_commands.c
|
||||
|
||||
# command definitions from modules (may be empty at Makefile parsing time...)
|
||||
MODULE_COMMANDS = $(subst COMMAND.,,$(notdir $(wildcard $(WORK_DIR)builtin_commands/COMMAND.*)))
|
||||
|
||||
# We must have at least one pre-defined builtin command in order to generate
|
||||
# any of this.
|
||||
#
|
||||
ifneq ($(BUILTIN_COMMANDS),)
|
||||
|
||||
# (BUILTIN_PROTO,<cmdspec>,<outputfile>)
|
||||
define BUILTIN_PROTO
|
||||
$(ECHO) 'extern int $(word 4,$1)(int argc, char *argv[]);' >> $2;
|
||||
endef
|
||||
|
||||
# (BUILTIN_DEF,<cmdspec>,<outputfile>)
|
||||
define BUILTIN_DEF
|
||||
$(ECHO) ' {"$(word 1,$1)", $(word 2,$1), $(word 3,$1), $(word 4,$1)},' >> $2;
|
||||
endef
|
||||
|
||||
# Don't generate until modules have updated their command files
|
||||
$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(MODULE_OBJS) $(MODULE_MKFILES) $(BUILTIN_COMMAND_FILES)
|
||||
@$(ECHO) "CMDS: $@"
|
||||
$(Q) $(ECHO) '/* builtin command list - automatically generated, do not edit */' > $@
|
||||
$(Q) $(ECHO) '#include <nuttx/config.h>' >> $@
|
||||
$(Q) $(ECHO) '#include <nuttx/binfmt/builtin.h>' >> $@
|
||||
$(Q) $(foreach spec,$(BUILTIN_COMMANDS),$(call BUILTIN_PROTO,$(subst ., ,$(spec)),$@))
|
||||
$(Q) $(foreach spec,$(MODULE_COMMANDS),$(call BUILTIN_PROTO,$(subst ., ,$(spec)),$@))
|
||||
$(Q) $(ECHO) 'const struct builtin_s g_builtins[] = {' >> $@
|
||||
$(Q) $(foreach spec,$(BUILTIN_COMMANDS),$(call BUILTIN_DEF,$(subst ., ,$(spec)),$@))
|
||||
$(Q) $(foreach spec,$(MODULE_COMMANDS),$(call BUILTIN_DEF,$(subst ., ,$(spec)),$@))
|
||||
$(Q) $(ECHO) ' {NULL, 0, 0, NULL}' >> $@
|
||||
$(Q) $(ECHO) '};' >> $@
|
||||
$(Q) $(ECHO) 'const int g_builtin_count = $(words $(BUILTIN_COMMANDS) $(MODULE_COMMANDS));' >> $@
|
||||
|
||||
SRCS += $(BUILTIN_CSRC)
|
||||
|
||||
EXTRA_CLEANS += $(BUILTIN_CSRC)
|
||||
|
||||
endif
|
||||
|
||||
################################################################################
|
||||
# Build rules
|
||||
################################################################################
|
||||
|
||||
#
|
||||
# What we're going to build.
|
||||
#
|
||||
PRODUCT_BUNDLE = $(WORK_DIR)firmware.px4
|
||||
PRODUCT_BIN = $(WORK_DIR)firmware.bin
|
||||
PRODUCT_ELF = $(WORK_DIR)firmware.elf
|
||||
PRODUCT_PARAMXML = $(WORK_DIR)/parameters.xml
|
||||
|
||||
.PHONY: firmware
|
||||
firmware: $(PRODUCT_BUNDLE)
|
||||
|
||||
#
|
||||
# Built product rules
|
||||
#
|
||||
|
||||
$(PRODUCT_BUNDLE): $(PRODUCT_BIN)
|
||||
@$(ECHO) %% Generating $@
|
||||
ifdef GEN_PARAM_XML
|
||||
python $(PX4_BASE)/Tools/px_process_params.py --src-path $(PX4_BASE)/src --board CONFIG_ARCH_BOARD_$(CONFIG_BOARD) --xml
|
||||
$(Q) $(MKFW) --prototype $(IMAGE_DIR)/$(BOARD).prototype \
|
||||
--git_identity $(PX4_BASE) \
|
||||
--parameter_xml $(PRODUCT_PARAMXML) \
|
||||
--image $< > $@
|
||||
else
|
||||
$(Q) $(MKFW) --prototype $(IMAGE_DIR)/$(BOARD).prototype \
|
||||
--git_identity $(PX4_BASE) \
|
||||
--image $< > $@
|
||||
endif
|
||||
|
||||
$(PRODUCT_BIN): $(PRODUCT_ELF)
|
||||
$(call SYM_TO_BIN,$<,$@)
|
||||
|
||||
$(PRODUCT_ELF): $(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKFILES)
|
||||
$(call LINK,$@,$(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS))
|
||||
|
||||
#
|
||||
# Utility rules
|
||||
#
|
||||
|
||||
.PHONY: upload
|
||||
upload: $(PRODUCT_BUNDLE) $(PRODUCT_BIN)
|
||||
$(Q) $(MAKE) -f $(PX4_MK_DIR)/upload.mk \
|
||||
METHOD=serial \
|
||||
CONFIG=$(CONFIG) \
|
||||
BOARD=$(BOARD) \
|
||||
BUNDLE=$(PRODUCT_BUNDLE) \
|
||||
BIN=$(PRODUCT_BIN)
|
||||
|
||||
.PHONY: clean
|
||||
clean: $(MODULE_CLEANS)
|
||||
@$(ECHO) %% cleaning
|
||||
$(Q) $(REMOVE) $(PRODUCT_BUNDLE) $(PRODUCT_BIN) $(PRODUCT_ELF)
|
||||
$(Q) $(REMOVE) $(OBJS) $(DEP_INCLUDES) $(EXTRA_CLEANS)
|
||||
$(Q) $(RMDIR) $(NUTTX_EXPORT_DIR)
|
||||
|
||||
@@ -0,0 +1,40 @@
|
||||
#
|
||||
# Copyright (C) 2012 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.
|
||||
#
|
||||
|
||||
#
|
||||
# Rules and definitions related to handling the Linux specific impl when
|
||||
# building firmware.
|
||||
#
|
||||
|
||||
MODULES += \
|
||||
platforms/common \
|
||||
platforms/posix/px4_layer
|
||||
|
||||
@@ -0,0 +1,11 @@
|
||||
#
|
||||
# Board-specific definitions for the POSIX port of PX4
|
||||
#
|
||||
|
||||
#
|
||||
# Configure the toolchain
|
||||
#
|
||||
CONFIG_ARCH = NATIVE
|
||||
CONFIG_BOARD = POSIXTEST
|
||||
|
||||
include $(PX4_MK_DIR)/toolchain_native.mk
|
||||
@@ -0,0 +1,78 @@
|
||||
#
|
||||
# Makefile for the POSIXTEST *default* configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/blinkm
|
||||
MODULES += drivers/hil
|
||||
MODULES += drivers/rgbled
|
||||
MODULES += drivers/led
|
||||
MODULES += modules/sensors
|
||||
#MODULES += drivers/ms5611
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
MODULES += systemcmds/param
|
||||
MODULES += systemcmds/mixer
|
||||
MODULES += systemcmds/topic_listener
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
MODULES += modules/mavlink
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
MODULES += modules/attitude_estimator_ekf
|
||||
MODULES += modules/ekf_att_pos_estimator
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
MODULES += modules/mc_pos_control
|
||||
MODULES += modules/mc_att_control
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
MODULES += modules/systemlib
|
||||
MODULES += modules/systemlib/mixer
|
||||
MODULES += modules/uORB
|
||||
MODULES += modules/dataman
|
||||
MODULES += modules/sdlog2
|
||||
MODULES += modules/simulator
|
||||
MODULES += modules/commander
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
MODULES += lib/mathlib
|
||||
MODULES += lib/mathlib/math/filter
|
||||
MODULES += lib/geo
|
||||
MODULES += lib/geo_lookup
|
||||
MODULES += lib/conversion
|
||||
|
||||
#
|
||||
# Linux port
|
||||
#
|
||||
MODULES += platforms/posix/px4_layer
|
||||
MODULES += platforms/posix/drivers/accelsim
|
||||
MODULES += platforms/posix/drivers/gyrosim
|
||||
MODULES += platforms/posix/drivers/adcsim
|
||||
MODULES += platforms/posix/drivers/barosim
|
||||
MODULES += platforms/posix/drivers/tonealrmsim
|
||||
MODULES += platforms/posix/drivers/airspeedsim
|
||||
|
||||
#
|
||||
# Unit tests
|
||||
#
|
||||
#MODULES += platforms/posix/tests/hello
|
||||
#MODULES += platforms/posix/tests/vcdev_test
|
||||
#MODULES += platforms/posix/tests/hrt_test
|
||||
#MODULES += platforms/posix/tests/wqueue
|
||||
|
||||
@@ -0,0 +1,73 @@
|
||||
#
|
||||
# Copyright (C) 2012 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.
|
||||
#
|
||||
|
||||
#
|
||||
# Makefile for PX4 POSIX based firmware images.
|
||||
#
|
||||
|
||||
################################################################################
|
||||
# Build rules
|
||||
################################################################################
|
||||
|
||||
#
|
||||
# What we're going to build.
|
||||
#
|
||||
PRODUCT_SHARED_LIB = $(WORK_DIR)firmware.a
|
||||
PRODUCT_SHARED_PRELINK = $(WORK_DIR)firmware.o
|
||||
|
||||
.PHONY: firmware
|
||||
firmware: $(PRODUCT_SHARED_LIB) $(WORK_DIR)mainapp
|
||||
|
||||
#
|
||||
# Built product rules
|
||||
#
|
||||
|
||||
$(PRODUCT_SHARED_PRELINK): $(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKFILES)
|
||||
$(call PRELINKF,$@,$(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS))
|
||||
|
||||
$(PRODUCT_SHARED_LIB): $(PRODUCT_SHARED_PRELINK)
|
||||
$(call LINK_A,$@,$(PRODUCT_SHARED_PRELINK))
|
||||
|
||||
MAIN = $(PX4_BASE)/src/platforms/posix/main.cpp
|
||||
$(WORK_DIR)mainapp: $(PRODUCT_SHARED_LIB)
|
||||
$(PX4_BASE)/Tools/posix_apps.py > apps.h
|
||||
$(call LINK,$@, -I. $(MAIN) $(PRODUCT_SHARED_LIB))
|
||||
|
||||
#
|
||||
# Utility rules
|
||||
#
|
||||
|
||||
.PHONY: clean
|
||||
clean: $(MODULE_CLEANS)
|
||||
@$(ECHO) %% cleaning
|
||||
$(Q) $(REMOVE) $(PRODUCT_ELF)
|
||||
$(Q) $(REMOVE) $(OBJS) $(DEP_INCLUDES) $(EXTRA_CLEANS)
|
||||
|
||||
@@ -0,0 +1,39 @@
|
||||
#
|
||||
# Copyright (C) 2015 Mark Charlebois. 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.
|
||||
#
|
||||
|
||||
#
|
||||
# Rules and definitions related to handling the Linux specific impl when
|
||||
# building firmware.
|
||||
#
|
||||
|
||||
MODULES += \
|
||||
platforms/common
|
||||
|
||||
@@ -0,0 +1,11 @@
|
||||
#
|
||||
# Board-specific definitions for the Linux port of PX4
|
||||
#
|
||||
|
||||
#
|
||||
# Configure the toolchain
|
||||
#
|
||||
CONFIG_ARCH = HEXAGON
|
||||
CONFIG_BOARD = QURTTEST
|
||||
|
||||
include $(PX4_MK_DIR)/toolchain_hexagon.mk
|
||||
@@ -0,0 +1,78 @@
|
||||
#
|
||||
# Makefile for the Foo *default* configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Use the configuration's ROMFS.
|
||||
#
|
||||
#ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/blinkm
|
||||
MODULES += drivers/hil
|
||||
MODULES += drivers/led
|
||||
MODULES += drivers/rgbled
|
||||
#MODULES += modules/sensors
|
||||
#MODULES += drivers/ms5611
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
MODULES += systemcmds/param
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
#MODULES += modules/mavlink
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
#MODULES += modules/attitude_estimator_ekf
|
||||
#MODULES += modules/ekf_att_pos_estimator
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
#MODULES += modules/mc_att_control
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
MODULES += modules/systemlib
|
||||
MODULES += modules/systemlib/mixer
|
||||
MODULES += modules/uORB
|
||||
#MODULES += modules/dataman
|
||||
#MODULES += modules/sdlog2
|
||||
MODULES += modules/simulator
|
||||
#MODULES += modules/commander
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
MODULES += lib/mathlib
|
||||
MODULES += lib/mathlib/math/filter
|
||||
#MODULES += lib/geo
|
||||
#MODULES += lib/geo_lookup
|
||||
MODULES += lib/conversion
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
#
|
||||
MODULES += platforms/qurt/px4_layer
|
||||
MODULES += platforms/posix/drivers/accelsim
|
||||
MODULES += platforms/posix/drivers/gyrosim
|
||||
MODULES += platforms/posix/drivers/adcsim
|
||||
MODULES += platforms/posix/drivers/barosim
|
||||
|
||||
#
|
||||
# Unit tests
|
||||
#
|
||||
MODULES += platforms/qurt/tests/hello
|
||||
MODULES += platforms/posix/tests/vcdev_test
|
||||
MODULES += platforms/posix/tests/hrt_test
|
||||
MODULES += platforms/posix/tests/wqueue
|
||||
|
||||
@@ -0,0 +1,17 @@
|
||||
This patch is required for QuRT. complex.h defines "I" and it replaces "I" in the
|
||||
enum definition without this patch creating an error.
|
||||
|
||||
diff --git a/Eigen/src/Core/SolveTriangular.h b/Eigen/src/Core/SolveTriangular.h
|
||||
index ef17f28..1116270 100644
|
||||
--- a/Eigen/src/Core/SolveTriangular.h
|
||||
+++ b/Eigen/src/Core/SolveTriangular.h
|
||||
@@ -112,6 +112,9 @@ template<typename Lhs, typename Rhs, int Mode, int Index, int Size,
|
||||
bool Stop = Index==Size>
|
||||
struct triangular_solver_unroller;
|
||||
|
||||
+#ifdef __PX4_QURT
|
||||
+#undef I
|
||||
+#endif
|
||||
template<typename Lhs, typename Rhs, int Mode, int Index, int Size>
|
||||
struct triangular_solver_unroller<Lhs,Rhs,Mode,Index,Size,false> {
|
||||
enum {
|
||||
@@ -0,0 +1,77 @@
|
||||
#
|
||||
# Copyright (C) 2012 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.
|
||||
#
|
||||
|
||||
#
|
||||
# Makefile for PX4 Linux based firmware images.
|
||||
#
|
||||
|
||||
################################################################################
|
||||
# Build rules
|
||||
################################################################################
|
||||
|
||||
#
|
||||
# What we're going to build.
|
||||
#
|
||||
PRODUCT_SHARED_LIB = $(WORK_DIR)firmware.a
|
||||
PRODUCT_SHARED_PRELINK = $(WORK_DIR)firmware.o
|
||||
|
||||
.PHONY: firmware
|
||||
firmware: $(PRODUCT_SHARED_LIB) $(WORK_DIR)mainapp
|
||||
|
||||
#
|
||||
# Built product rules
|
||||
#
|
||||
|
||||
$(PRODUCT_SHARED_PRELINK): $(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKFILES)
|
||||
$(call PRELINKF,$@,$(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS))
|
||||
|
||||
$(PRODUCT_SHARED_LIB): $(PRODUCT_SHARED_PRELINK)
|
||||
$(call LINK_A,$@,$(PRODUCT_SHARED_PRELINK))
|
||||
|
||||
$(WORK_DIR)apps.cpp: $(PX4_BASE)/Tools/qurt_apps.py
|
||||
$(PX4_BASE)/Tools/qurt_apps.py > $@
|
||||
|
||||
$(WORK_DIR)apps.o: $(WORK_DIR)apps.cpp
|
||||
$(call COMPILEXX,$<, $@)
|
||||
mv $(WORK_DIR)apps.cpp $(WORK_DIR)apps.cpp_sav
|
||||
|
||||
$(WORK_DIR)mainapp: $(WORK_DIR)apps.o $(PRODUCT_SHARED_LIB)
|
||||
$(call LINK,$@, $^)
|
||||
|
||||
#
|
||||
# Utility rules
|
||||
#
|
||||
|
||||
.PHONY: clean
|
||||
clean: $(MODULE_CLEANS)
|
||||
@$(ECHO) %% cleaning
|
||||
$(Q) $(REMOVE) $(PRODUCT_ELF)
|
||||
$(Q) $(REMOVE) $(OBJS) $(DEP_INCLUDES) $(EXTRA_CLEANS)
|
||||
+8
-1
@@ -33,6 +33,13 @@
|
||||
# Path and tool setup
|
||||
#
|
||||
|
||||
export PX4_TARGET_OS ?= nuttx
|
||||
|
||||
# PX4_TARGET_OS can be nuttx, posix, or qurt
|
||||
ifeq ($(PX4_TARGET_OS),)
|
||||
$(error Use: make PX4_TARGET_OS=<target> where <target> is nuttx, posix, or qurt)
|
||||
endif
|
||||
|
||||
#
|
||||
# Some useful paths.
|
||||
#
|
||||
@@ -47,8 +54,8 @@ export PX4_LIB_DIR = $(abspath $(PX4_BASE)/src/lib)/
|
||||
export PX4_PLATFORMS_DIR = $(abspath $(PX4_BASE)/src/platforms)/
|
||||
export PX4_MK_DIR = $(abspath $(PX4_BASE)/makefiles)/
|
||||
export NUTTX_SRC = $(abspath $(PX4_BASE)/NuttX/nuttx)/
|
||||
export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink/include/mavlink/v1.0)/
|
||||
export NUTTX_APP_SRC = $(abspath $(PX4_BASE)/NuttX/apps)/
|
||||
#export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink/include/mavlink/v1.0)/
|
||||
export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink)/
|
||||
export UAVCAN_DIR = $(abspath $(PX4_BASE)/uavcan)/
|
||||
export ROMFS_SRC = $(abspath $(PX4_BASE)/ROMFS)/
|
||||
|
||||
@@ -107,7 +107,7 @@ endif
|
||||
ifeq ($(CONFIG_BOARD),)
|
||||
$(error Board config does not define CONFIG_BOARD)
|
||||
endif
|
||||
ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD)
|
||||
ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) -D__PX4_NUTTX
|
||||
|
||||
# optimisation flags
|
||||
#
|
||||
@@ -138,7 +138,6 @@ ARCHWARNINGS = -Wall \
|
||||
-Wdouble-promotion \
|
||||
-Wshadow \
|
||||
-Wfloat-equal \
|
||||
-Wframe-larger-than=1024 \
|
||||
-Wpointer-arith \
|
||||
-Wlogical-op \
|
||||
-Wmissing-declarations \
|
||||
|
||||
@@ -0,0 +1,314 @@
|
||||
#
|
||||
# Copyright (C) 2015 Mark Charlebois. 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.
|
||||
#
|
||||
|
||||
#
|
||||
# Definitions for a generic GNU ARM-EABI toolchain
|
||||
#
|
||||
|
||||
#$(info TOOLCHAIN gnu-arm-eabi)
|
||||
|
||||
# Toolchain commands. Normally only used inside this file.
|
||||
#
|
||||
HEXAGON_TOOLS_ROOT = /opt/6.4.05
|
||||
HEXAGON_SDK_ROOT = /opt/Hexagon_SDK/2.0
|
||||
#V_ARCH = v4
|
||||
V_ARCH = v5
|
||||
CROSSDEV = hexagon-
|
||||
HEXAGON_BIN = $(addsuffix /gnu/bin,$(HEXAGON_TOOLS_ROOT))
|
||||
HEXAGON_CLANG_BIN = $(addsuffix /qc/bin,$(HEXAGON_TOOLS_ROOT))
|
||||
HEXAGON_LIB_DIR = $(HEXAGON_TOOLS_ROOT)/gnu/hexagon/lib
|
||||
HEXAGON_ISS_DIR = $(HEXAGON_TOOLS_ROOT)/qc/lib/iss
|
||||
TOOLSLIB = $(HEXAGON_TOOLS_ROOT)/dinkumware/lib/$(V_ARCH)/G0
|
||||
QCTOOLSLIB = $(HEXAGON_TOOLS_ROOT)/qc/lib/$(V_ARCH)/G0
|
||||
QURTLIB = $(HEXAGON_SDK_ROOT)/lib/common/qurt/ADSP$(V_ARCH)MP/lib
|
||||
#DSPAL = $(PX4_BASE)/../dspal_libs/libdspal.a
|
||||
|
||||
|
||||
CC = $(HEXAGON_CLANG_BIN)/$(CROSSDEV)clang
|
||||
CXX = $(HEXAGON_CLANG_BIN)/$(CROSSDEV)clang++
|
||||
CPP = $(HEXAGON_CLANG_BIN)/$(CROSSDEV)clang -E
|
||||
LD = $(HEXAGON_BIN)/$(CROSSDEV)ld
|
||||
AR = $(HEXAGON_BIN)/$(CROSSDEV)ar rcs
|
||||
NM = $(HEXAGON_BIN)/$(CROSSDEV)nm
|
||||
OBJCOPY = $(HEXAGON_BIN)/$(CROSSDEV)objcopy
|
||||
OBJDUMP = $(HEXAGON_BIN)/$(CROSSDEV)objdump
|
||||
|
||||
QURTLIBS = \
|
||||
$(TOOLSLIB)/init.o \
|
||||
$(TOOLSLIB)/libc.a \
|
||||
$(TOOLSLIB)/libqcc.a \
|
||||
$(TOOLSLIB)/libstdc++.a \
|
||||
$(QURTLIB)/crt0.o \
|
||||
$(QURTLIB)/libqurt.a \
|
||||
$(QURTLIB)/libqurtkernel.a \
|
||||
$(QURTLIB)/libqurtcfs.a \
|
||||
$(QURTLIB)/libqube_compat.a \
|
||||
$(QURTLIB)/libtimer.a \
|
||||
$(QURTLIB)/libposix.a \
|
||||
$(QURTLIB)/../examples/cust_config.o \
|
||||
$(QCTOOLSLIB)/libhexagon.a \
|
||||
$(TOOLSLIB)/fini.o
|
||||
|
||||
|
||||
|
||||
|
||||
# Check if the right version of the toolchain is available
|
||||
#
|
||||
CROSSDEV_VER_SUPPORTED = 6.4.05
|
||||
CROSSDEV_VER_FOUND = $(shell $(CC) --version | sed -n 's/^.*version \([\. 0-9]*\),.*$$/\1/p')
|
||||
|
||||
ifeq (,$(findstring $(CROSSDEV_VER_FOUND), $(CROSSDEV_VER_SUPPORTED)))
|
||||
$(error Unsupported version of $(CC), found: $(CROSSDEV_VER_FOUND) instead of one in: $(CROSSDEV_VER_SUPPORTED))
|
||||
endif
|
||||
|
||||
|
||||
# XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup
|
||||
|
||||
MAXOPTIMIZATION ?= -O0
|
||||
|
||||
# Base CPU flags for each of the supported architectures.
|
||||
#
|
||||
ARCHCPUFLAGS = -m$(V_ARCH)
|
||||
|
||||
|
||||
# Set the board flags
|
||||
#
|
||||
ifeq ($(CONFIG_BOARD),)
|
||||
$(error Board config does not define CONFIG_BOARD)
|
||||
endif
|
||||
ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) \
|
||||
-D__PX4_QURT -D__PX4_POSIX \
|
||||
-D__EXPORT= \
|
||||
-D__QDSP6_DINKUM_PTHREAD_TYPES__ \
|
||||
-Dnoreturn_function= \
|
||||
-Drestrict= \
|
||||
-I$(HEXAGON_TOOLS_ROOT)/gnu/hexagon/include \
|
||||
-I$(PX4_BASE)/src/lib/eigen \
|
||||
-I$(PX4_BASE)/src/platforms/qurt/include \
|
||||
-I$(PX4_BASE)/../dspal/include \
|
||||
-I$(PX4_BASE)/../dspal/sys \
|
||||
-I$(PX4_BASE)/mavlink/include/mavlink \
|
||||
-I$(QURTLIB)/..//include \
|
||||
-Wno-error=shadow
|
||||
|
||||
# optimisation flags
|
||||
#
|
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
|
||||
-g3 \
|
||||
-fno-strict-aliasing \
|
||||
-fomit-frame-pointer \
|
||||
-funsafe-math-optimizations \
|
||||
-ffunction-sections \
|
||||
-fdata-sections
|
||||
|
||||
# enable precise stack overflow tracking
|
||||
# note - requires corresponding support in NuttX
|
||||
INSTRUMENTATIONDEFINES = $(ARCHINSTRUMENTATIONDEFINES_$(CONFIG_ARCH))
|
||||
|
||||
# Language-specific flags
|
||||
#
|
||||
ARCHCFLAGS = -std=gnu99
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x -fno-threadsafe-statics -D__CUSTOM_FILE_IO__
|
||||
|
||||
# Generic warnings
|
||||
#
|
||||
ARCHWARNINGS = -Wall \
|
||||
-Wextra \
|
||||
-Werror \
|
||||
-Wno-unused-parameter \
|
||||
-Wno-unused-function \
|
||||
-Wno-unused-variable \
|
||||
-Wno-gnu-array-member-paren-init \
|
||||
-Wno-cast-align \
|
||||
-Wno-missing-braces \
|
||||
-Wno-strict-aliasing
|
||||
# -Werror=float-conversion - works, just needs to be phased in with some effort and needs GCC 4.9+
|
||||
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
|
||||
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
|
||||
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
|
||||
|
||||
# C-specific warnings
|
||||
#
|
||||
ARCHCWARNINGS = $(ARCHWARNINGS) \
|
||||
-Wstrict-prototypes \
|
||||
-Wnested-externs
|
||||
|
||||
# C++-specific warnings
|
||||
#
|
||||
ARCHWARNINGSXX = $(ARCHWARNINGS) \
|
||||
-Wno-missing-field-initializers
|
||||
|
||||
# pull in *just* libm from the toolchain ... this is grody
|
||||
LIBM := $(shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a)
|
||||
EXTRA_LIBS += $(LIBM)
|
||||
|
||||
# Flags we pass to the C compiler
|
||||
#
|
||||
CFLAGS = $(ARCHCFLAGS) \
|
||||
$(ARCHCWARNINGS) \
|
||||
$(ARCHOPTIMIZATION) \
|
||||
$(ARCHCPUFLAGS) \
|
||||
$(ARCHINCLUDES) \
|
||||
$(INSTRUMENTATIONDEFINES) \
|
||||
$(ARCHDEFINES) \
|
||||
$(EXTRADEFINES) \
|
||||
$(EXTRACFLAGS) \
|
||||
-fno-common \
|
||||
$(addprefix -I,$(INCLUDE_DIRS))
|
||||
|
||||
# Flags we pass to the C++ compiler
|
||||
#
|
||||
CXXFLAGS = $(ARCHCXXFLAGS) \
|
||||
$(ARCHWARNINGSXX) \
|
||||
$(ARCHOPTIMIZATION) \
|
||||
$(ARCHCPUFLAGS) \
|
||||
$(ARCHXXINCLUDES) \
|
||||
$(INSTRUMENTATIONDEFINES) \
|
||||
$(ARCHDEFINES) \
|
||||
-DCONFIG_WCHAR_BUILTIN \
|
||||
$(EXTRADEFINES) \
|
||||
$(EXTRACXXFLAGS) \
|
||||
$(addprefix -I,$(INCLUDE_DIRS))
|
||||
|
||||
ifeq (1,$(V_dynamic))
|
||||
CXX_FLAGS += -fpic -D__V_DYNAMIC__
|
||||
endif
|
||||
|
||||
# Flags we pass to the assembler
|
||||
#
|
||||
AFLAGS = $(CFLAGS) -D__ASSEMBLY__ \
|
||||
$(EXTRADEFINES) \
|
||||
$(EXTRAAFLAGS)
|
||||
|
||||
LDSCRIPT = $(PX4_BASE)/posix-configs/posixtest/scripts/ld.script
|
||||
# Flags we pass to the linker
|
||||
#
|
||||
LDFLAGS += -g -nostdlib --section-start .start=0x1d000000\
|
||||
$(EXTRALDFLAGS) \
|
||||
$(addprefix -L,$(LIB_DIRS))
|
||||
|
||||
# Compiler support library
|
||||
#
|
||||
LIBGCC := $(shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name)
|
||||
|
||||
# Files that the final link depends on
|
||||
#
|
||||
LINK_DEPS += $(LDSCRIPT)
|
||||
|
||||
# Files to include to get automated dependencies
|
||||
#
|
||||
DEP_INCLUDES = $(subst .o,.d,$(OBJS))
|
||||
|
||||
# Compile C source $1 to object $2
|
||||
# as a side-effect, generate a dependency file
|
||||
#
|
||||
define COMPILE
|
||||
@$(ECHO) "CC: $1"
|
||||
@$(MKDIR) -p $(dir $2)
|
||||
@echo $(Q) $(CCACHE) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2
|
||||
$(Q) $(CCACHE) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2
|
||||
endef
|
||||
|
||||
# Compile C++ source $1 to $2
|
||||
# as a side-effect, generate a dependency file
|
||||
#
|
||||
define COMPILEXX
|
||||
@$(ECHO) "CXX: $1"
|
||||
@$(MKDIR) -p $(dir $2)
|
||||
@echo $(Q) $(CCACHE) $(CXX) -MD -c $(CXXFLAGS) $(abspath $1) -o $2
|
||||
$(Q) $(CCACHE) $(CXX) -MD -c $(CXXFLAGS) $(abspath $1) -o $2
|
||||
endef
|
||||
|
||||
# Assemble $1 into $2
|
||||
#
|
||||
define ASSEMBLE
|
||||
@$(ECHO) "AS: $1"
|
||||
@$(MKDIR) -p $(dir $2)
|
||||
$(Q) $(CC) -c $(AFLAGS) $(abspath $1) -o $2
|
||||
endef
|
||||
|
||||
# Produce partially-linked $1 from files in $2
|
||||
#
|
||||
#$(Q) $(LD) -Ur -o $1 $2 # -Ur not supported in ld.gold
|
||||
define PRELINK
|
||||
@$(ECHO) "PRELINK: $1"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
@echo $(Q) $(LD) -Ur -o $1 $2
|
||||
$(Q) $(LD) -Ur -o $1 $2
|
||||
|
||||
endef
|
||||
# Produce partially-linked $1 from files in $2
|
||||
#
|
||||
#$(Q) $(LD) -Ur -o $1 $2 # -Ur not supported in ld.gold
|
||||
define PRELINKF
|
||||
@$(ECHO) "PRELINKF: $1"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
@echo $(Q) $(LD) -Ur -T$(LDSCRIPT) -o $1 $2
|
||||
$(Q) $(LD) -Ur -T$(LDSCRIPT) -o $1 $2
|
||||
|
||||
endef
|
||||
# $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
|
||||
|
||||
# Update the archive $1 with the files in $2
|
||||
#
|
||||
define ARCHIVE
|
||||
@$(ECHO) "AR: $2"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
$(Q) $(AR) $1 $2
|
||||
endef
|
||||
|
||||
# Link the objects in $2 into the shared library $1
|
||||
#
|
||||
define LINK_A
|
||||
@$(ECHO) "LINK_A: $1"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
echo "$(Q) $(AR) $1 $2"
|
||||
$(Q) $(AR) $1 $2
|
||||
endef
|
||||
|
||||
# Link the objects in $2 into the shared library $1
|
||||
#
|
||||
define LINK_SO
|
||||
@$(ECHO) "LINK_SO: $1"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
echo "$(Q) $(CXX) $(LDFLAGS) -shared -Wl,-soname,`basename $1`.1 -o $1 $2 $(LIBS) $(EXTRA_LIBS)"
|
||||
$(Q) $(CXX) $(LDFLAGS) -shared -Wl,-soname,`basename $1`.1 -o $1 $2 $(LIBS) -pthread -lc
|
||||
endef
|
||||
|
||||
# Link the objects in $2 into the application $1
|
||||
#
|
||||
define LINK
|
||||
@$(ECHO) "LINK: $1"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
@echo $(Q) $(LD) $(LDFLAGS) -o $1 --start-group $2 $(EXTRA_LIBS) $(QURTLIBS) --end-group
|
||||
$(Q) $(LD) $(LDFLAGS) -o $1 --start-group $2 $(EXTRA_LIBS) $(QURTLIBS) --end-group
|
||||
endef
|
||||
|
||||
@@ -0,0 +1,357 @@
|
||||
#
|
||||
# Copyright (C) 2012-2014 PX4 Development Team. All rights reuint32_tserved.
|
||||
#
|
||||
# 2005 Modified for clang and GCC on POSIX:
|
||||
# Author: Mark Charlebois <charlebm@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.
|
||||
#
|
||||
|
||||
#
|
||||
# Definitions for a native GCC toolchain
|
||||
#
|
||||
|
||||
#$(info TOOLCHAIN native)
|
||||
|
||||
# Toolchain commands. Normally only used inside this file.
|
||||
#
|
||||
|
||||
# Set to 1 for GCC-4.8.2 and to 0 for Clang-3.5 (Ubuntu 14.04)
|
||||
USE_GCC?=0
|
||||
|
||||
ifneq ($(USE_GCC),1)
|
||||
|
||||
HAVE_CLANG35:=$(shell clang-3.5 -dumpversion 2>/dev/null)
|
||||
|
||||
# Clang will report 4.2.1 as GCC version
|
||||
HAVE_CLANG:=$(shell clang -dumpversion)
|
||||
|
||||
#If using ubuntu 14.04 and packaged clang 3.5
|
||||
ifeq ($(HAVE_CLANG35),4.2.1)
|
||||
USE_GCC=0
|
||||
CLANGVER=-3.5
|
||||
else
|
||||
|
||||
#If using ubuntu 12.04 and downloaded clang 3.4.2
|
||||
ifeq ($(HAVE_CLANG),4.2.1)
|
||||
USE_GCC=0
|
||||
CLANGVER=
|
||||
endif
|
||||
endif
|
||||
|
||||
# If no version of clang was found
|
||||
ifeq ($(HAVE_CLANG35),)
|
||||
ifeq ($(HAVE_CLANG),)
|
||||
$(error Clang not found. Try make USE_GCC=1)
|
||||
endif
|
||||
endif
|
||||
endif # USE_GCC is not 1
|
||||
|
||||
ifeq ($(USE_GCC),1)
|
||||
# GCC Options:
|
||||
CC = gcc
|
||||
CXX = g++
|
||||
CPP = gcc -E
|
||||
|
||||
# GCC Version
|
||||
DEV_VER_SUPPORTED = 4.8.1 4.8.2 4.9.1
|
||||
|
||||
else
|
||||
# Clang options
|
||||
CC = clang$(CLANGVER)
|
||||
CXX = clang++$(CLANGVER)
|
||||
CPP = clang$(CLANGVER) -E
|
||||
|
||||
# Clang GCC reported version
|
||||
DEV_VER_SUPPORTED = 4.2.1
|
||||
endif
|
||||
|
||||
#LD = ld.gold
|
||||
LD = ld.bfd
|
||||
AR = ar rcs
|
||||
NM = nm
|
||||
OBJCOPY = objcopy
|
||||
OBJDUMP = objdump
|
||||
|
||||
# Check if the right version of the toolchain is available
|
||||
#
|
||||
DEV_VER_FOUND = $(shell $(CC) -dumpversion)
|
||||
|
||||
ifeq (,$(findstring $(DEV_VER_FOUND), $(DEV_VER_SUPPORTED)))
|
||||
$(error Unsupported version of $(CC), found: $(DEV_VER_FOUND) instead of one in: $(DEV_VER_SUPPORTED))
|
||||
endif
|
||||
|
||||
|
||||
# XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup
|
||||
|
||||
MAXOPTIMIZATION ?= -O3
|
||||
|
||||
# Enabling stack checks if OS was build with them
|
||||
#
|
||||
|
||||
# Set the board flags
|
||||
#
|
||||
ifeq ($(CONFIG_BOARD),)
|
||||
$(error Board config does not define CONFIG_BOARD)
|
||||
endif
|
||||
ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) \
|
||||
-D__PX4_LINUX -D__PX4_POSIX \
|
||||
-Dnoreturn_function= \
|
||||
-I$(PX4_BASE)/src/modules/systemlib \
|
||||
-I$(PX4_BASE)/src/lib/eigen \
|
||||
-I$(PX4_BASE)/src/platforms/posix/include \
|
||||
-I$(PX4_BASE)/mavlink/include/mavlink \
|
||||
-Wno-error=shadow
|
||||
|
||||
# optimisation flags
|
||||
#
|
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
|
||||
-g3 \
|
||||
-fno-strict-aliasing \
|
||||
-fomit-frame-pointer \
|
||||
-funsafe-math-optimizations \
|
||||
-fno-builtin-printf \
|
||||
-ffunction-sections \
|
||||
-fdata-sections
|
||||
|
||||
# Language-specific flags
|
||||
#
|
||||
ARCHCFLAGS = -std=gnu99 -g
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=c++0x -fno-threadsafe-statics -D__CUSTOM_FILE_IO__ -g
|
||||
|
||||
# Generic warnings
|
||||
#
|
||||
# Disabled
|
||||
# -Wshadow - Breaks for the libeigen package headers
|
||||
# -Wframe-larger-than=1024 - Only needed for embedded
|
||||
|
||||
ARCHWARNINGS = -Wall \
|
||||
-Wextra \
|
||||
-Werror \
|
||||
-Wfloat-equal \
|
||||
-Wpointer-arith \
|
||||
-Wmissing-declarations \
|
||||
-Wpacked \
|
||||
-Wno-unused-parameter \
|
||||
-Wno-packed \
|
||||
-Werror=format-security \
|
||||
-Werror=array-bounds \
|
||||
-Wfatal-errors \
|
||||
-Werror=unused-variable \
|
||||
-Werror=reorder \
|
||||
-Werror=uninitialized \
|
||||
-Werror=init-self
|
||||
|
||||
# Add compiler specific options
|
||||
ifeq ($(USE_GCC),1)
|
||||
ARCHDEFINES += -Wno-error=logical-op
|
||||
ARCHWARNINGS += -Wdouble-promotion \
|
||||
-Wlogical-op \
|
||||
-Wformat=1 \
|
||||
-Werror=unused-but-set-variable \
|
||||
-Werror=double-promotion
|
||||
ARCHOPTIMIZATION += -fno-strength-reduce
|
||||
else
|
||||
ARCHWARNINGS += -Wno-gnu-array-member-paren-init
|
||||
endif
|
||||
|
||||
# -Werror=float-conversion - works, just needs to be phased in with some effort and needs GCC 4.9+
|
||||
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
|
||||
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
|
||||
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
|
||||
|
||||
# C-specific warnings
|
||||
#
|
||||
ARCHCWARNINGS = $(ARCHWARNINGS) \
|
||||
-Wbad-function-cast \
|
||||
-Wstrict-prototypes \
|
||||
-Wmissing-prototypes \
|
||||
-Wnested-externs
|
||||
|
||||
# Add compiler specific options
|
||||
ifeq ($(USE_GCC),1)
|
||||
ARCHCWARNINGS += -Wold-style-declaration \
|
||||
-Wmissing-parameter-type \
|
||||
-Wno-error=unused-local-typedefs \
|
||||
-Wno-error=enum-compare \
|
||||
-Wno-error=float-equal
|
||||
endif
|
||||
|
||||
# C++-specific warnings
|
||||
#
|
||||
ARCHWARNINGSXX = $(ARCHWARNINGS) \
|
||||
-Wno-missing-field-initializers
|
||||
|
||||
# pull in *just* libm from the toolchain ... this is grody
|
||||
LIBM := $(shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a)
|
||||
#EXTRA_LIBS += $(LIBM)
|
||||
EXTRA_LIBS += -pthread -lm -lrt
|
||||
|
||||
# Flags we pass to the C compiler
|
||||
#
|
||||
CFLAGS = $(ARCHCFLAGS) \
|
||||
$(ARCHCWARNINGS) \
|
||||
$(ARCHOPTIMIZATION) \
|
||||
$(ARCHCPUFLAGS) \
|
||||
$(ARCHINCLUDES) \
|
||||
$(INSTRUMENTATIONDEFINES) \
|
||||
$(ARCHDEFINES) \
|
||||
$(EXTRADEFINES) \
|
||||
$(EXTRACFLAGS) \
|
||||
-fno-common \
|
||||
$(addprefix -I,$(INCLUDE_DIRS))
|
||||
|
||||
# Flags we pass to the C++ compiler
|
||||
#
|
||||
CXXFLAGS = $(ARCHCXXFLAGS) \
|
||||
$(ARCHWARNINGSXX) \
|
||||
$(ARCHOPTIMIZATION) \
|
||||
$(ARCHCPUFLAGS) \
|
||||
$(ARCHXXINCLUDES) \
|
||||
$(INSTRUMENTATIONDEFINES) \
|
||||
$(ARCHDEFINES) \
|
||||
-DCONFIG_WCHAR_BUILTIN \
|
||||
$(EXTRADEFINES) \
|
||||
$(EXTRACXXFLAGS) \
|
||||
-Wno-effc++ \
|
||||
$(addprefix -I,$(INCLUDE_DIRS))
|
||||
|
||||
ifeq ($(USE_GCC),0)
|
||||
CXXFLAGS += -Wno-deprecated-register \
|
||||
-Wno-tautological-constant-out-of-range-compare \
|
||||
-Wno-unused-private-field \
|
||||
-Wno-unused-const-variable
|
||||
endif
|
||||
|
||||
# Flags we pass to the assembler
|
||||
#
|
||||
AFLAGS = $(CFLAGS) -D__ASSEMBLY__ \
|
||||
$(EXTRADEFINES) \
|
||||
$(EXTRAAFLAGS)
|
||||
|
||||
LDSCRIPT = $(PX4_BASE)/posix-configs/posixtest/scripts/ld.script
|
||||
# Flags we pass to the linker
|
||||
#
|
||||
LDFLAGS += $(EXTRALDFLAGS) \
|
||||
$(addprefix -L,$(LIB_DIRS))
|
||||
|
||||
# Compiler support library
|
||||
#
|
||||
LIBGCC := $(shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name)
|
||||
|
||||
# Files that the final link depends on
|
||||
#
|
||||
#LINK_DEPS += $(LDSCRIPT)
|
||||
LINK_DEPS +=
|
||||
|
||||
# Files to include to get automated dependencies
|
||||
#
|
||||
DEP_INCLUDES = $(subst .o,.d,$(OBJS))
|
||||
|
||||
# Compile C source $1 to object $2
|
||||
# as a side-effect, generate a dependency file
|
||||
#
|
||||
define COMPILE
|
||||
@$(ECHO) "CC: $1"
|
||||
@$(MKDIR) -p $(dir $2)
|
||||
$(Q) $(CCACHE) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2
|
||||
endef
|
||||
|
||||
# Compile C++ source $1 to $2
|
||||
# as a side-effect, generate a dependency file
|
||||
#
|
||||
define COMPILEXX
|
||||
@$(ECHO) "CXX: $1"
|
||||
@$(MKDIR) -p $(dir $2)
|
||||
@echo $(Q) $(CCACHE) $(CXX) -MD -c $(CXXFLAGS) $(abspath $1) -o $2
|
||||
$(Q) $(CCACHE) $(CXX) -MD -c $(CXXFLAGS) $(abspath $1) -o $2
|
||||
endef
|
||||
|
||||
# Assemble $1 into $2
|
||||
#
|
||||
define ASSEMBLE
|
||||
@$(ECHO) "AS: $1"
|
||||
@$(MKDIR) -p $(dir $2)
|
||||
$(Q) $(CC) -c $(AFLAGS) $(abspath $1) -o $2
|
||||
endef
|
||||
|
||||
# Produce partially-linked $1 from files in $2
|
||||
#
|
||||
#$(Q) $(LD) -Ur -o $1 $2 # -Ur not supported in ld.gold
|
||||
define PRELINK
|
||||
@$(ECHO) "PRELINK: $1"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
$(Q) $(LD) -Ur -o $1 $2
|
||||
|
||||
endef
|
||||
# Produce partially-linked $1 from files in $2
|
||||
#
|
||||
#$(Q) $(LD) -Ur -o $1 $2 # -Ur not supported in ld.gold
|
||||
define PRELINKF
|
||||
@$(ECHO) "PRELINK: $1"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
$(Q) $(LD) -Ur -T$(LDSCRIPT) -o $1 $2
|
||||
|
||||
endef
|
||||
# $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
|
||||
|
||||
# Update the archive $1 with the files in $2
|
||||
#
|
||||
define ARCHIVE
|
||||
@$(ECHO) "AR: $2"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
$(Q) $(AR) $1 $2
|
||||
endef
|
||||
|
||||
# Link the objects in $2 into the shared library $1
|
||||
#
|
||||
define LINK_A
|
||||
@$(ECHO) "LINK_A: $1"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
echo "$(Q) $(AR) $1 $2"
|
||||
$(Q) $(AR) $1 $2
|
||||
endef
|
||||
|
||||
# Link the objects in $2 into the shared library $1
|
||||
#
|
||||
define LINK_SO
|
||||
@$(ECHO) "LINK_SO: $1"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
echo "$(Q) $(CXX) $(LDFLAGS) -shared -Wl,-soname,`basename $1`.1 -o $1 $2 $(LIBS) $(EXTRA_LIBS)"
|
||||
$(Q) $(CXX) $(LDFLAGS) -shared -Wl,-soname,`basename $1`.1 -o $1 $2 $(LIBS) -pthread -lc
|
||||
endef
|
||||
|
||||
# Link the objects in $2 into the application $1
|
||||
#
|
||||
define LINK
|
||||
@$(ECHO) "LINK: $1"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
$(Q) $(CXX) $(CXXFLAGS) $(LDFLAGS) -o $1 $2 $(LIBS) $(EXTRA_LIBS) $(LIBGCC)
|
||||
|
||||
endef
|
||||
|
||||
+1
-1
@@ -31,7 +31,7 @@ upload-serial-px4fmu-v2: $(BUNDLE) $(UPLOADER)
|
||||
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
|
||||
|
||||
upload-serial-aerocore:
|
||||
openocd -f $(PX4_BASE)/makefiles/gumstix-aerocore.cfg -c 'init; reset halt; flash write_image erase $(PX4_BASE)/../Bootloader/px4aerocore_bl.bin 0x08000000; flash write_image erase $(PX4_BASE)/Build/aerocore_default.build/firmware.bin 0x08004000; reset run; exit'
|
||||
openocd -f $(PX4_BASE)/makefiles/nuttx/gumstix-aerocore.cfg -c 'init; reset halt; flash write_image erase $(PX4_BASE)/../Bootloader/px4aerocore_bl.bin 0x08000000; flash write_image erase $(PX4_BASE)/Build/aerocore_default.build/firmware.bin 0x08004000; reset run; exit'
|
||||
|
||||
upload-serial-px4-stm32f4discovery: $(BUNDLE) $(UPLOADER)
|
||||
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
|
||||
|
||||
@@ -0,0 +1,16 @@
|
||||
uorb start
|
||||
simulator start -s
|
||||
barosim start
|
||||
adcsim start
|
||||
accelsim start
|
||||
gyrosim start
|
||||
param set CAL_GYRO0_ID 2293760
|
||||
param set CAL_ACC0_ID 1310720
|
||||
param set CAL_ACC1_ID 1376256
|
||||
param set CAL_MAG0_ID 196608
|
||||
rgbled start
|
||||
mavlink start -d /tmp/ttyS0
|
||||
sensors start
|
||||
hil mode_pwm
|
||||
commander start
|
||||
list_devices
|
||||
@@ -0,0 +1,46 @@
|
||||
/****************************************************************************
|
||||
* ld.script
|
||||
*
|
||||
* Copyright (C) 2015 Mark Charlebois. All rights reserved.
|
||||
* Author: Mark Charlebois <charlebm@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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
/*
|
||||
* Construction data for parameters.
|
||||
*/
|
||||
__param : ALIGN(8) {
|
||||
__param_start = .;
|
||||
KEEP(*(__param*))
|
||||
__param_end = .;
|
||||
}
|
||||
}
|
||||
@@ -38,7 +38,7 @@
|
||||
* Driver for the Eagle Tree Airspeed V3 connected via I2C.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
||||
@@ -38,7 +38,7 @@
|
||||
* Generic driver for airspeed sensors connected via I2C.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
@@ -55,9 +55,14 @@
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/wqueue.h>
|
||||
#include <nuttx/clock.h>
|
||||
#
|
||||
#else
|
||||
#include <px4_workqueue.h>
|
||||
#endif
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
@@ -95,8 +100,8 @@ public:
|
||||
|
||||
virtual int init();
|
||||
|
||||
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
virtual ssize_t read(device::file_t *filp, char *buffer, size_t buflen);
|
||||
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Diagnostics - print some basic information about the driver.
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
* Implementation of AR.Drone 1.0 / 2.0 motor control interface.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
@@ -121,7 +121,7 @@ int ardrone_interface_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
ardrone_interface_task = task_spawn_cmd("ardrone_interface",
|
||||
ardrone_interface_task = px4_task_spawn_cmd("ardrone_interface",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 15,
|
||||
1100,
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
* Implementation of AR.Drone 1.0 / 2.0 motor control interface
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
|
||||
@@ -39,7 +39,7 @@
|
||||
* @author Randy Mackay <rmackay9@yahoo.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
||||
@@ -93,7 +93,7 @@
|
||||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
@@ -106,7 +106,7 @@
|
||||
#include <ctype.h>
|
||||
#include <poll.h>
|
||||
|
||||
#include <nuttx/wqueue.h>
|
||||
#include <px4_workqueue.h>
|
||||
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
@@ -140,7 +140,7 @@ public:
|
||||
virtual int init();
|
||||
virtual int probe();
|
||||
virtual int setMode(int mode);
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
|
||||
|
||||
static const char *const script_names[];
|
||||
|
||||
@@ -275,7 +275,11 @@ const char *const BlinkM::script_names[] = {
|
||||
extern "C" __EXPORT int blinkm_main(int argc, char *argv[]);
|
||||
|
||||
BlinkM::BlinkM(int bus, int blinkm) :
|
||||
I2C("blinkm", BLINKM0_DEVICE_PATH, bus, blinkm, 100000),
|
||||
I2C("blinkm", BLINKM0_DEVICE_PATH, bus, blinkm
|
||||
#ifdef __PX4_NUTTX
|
||||
, 100000
|
||||
#endif
|
||||
),
|
||||
led_color_1(LED_OFF),
|
||||
led_color_2(LED_OFF),
|
||||
led_color_3(LED_OFF),
|
||||
@@ -316,6 +320,7 @@ BlinkM::init()
|
||||
ret = I2C::init();
|
||||
|
||||
if (ret != OK) {
|
||||
warnx("I2C init failed");
|
||||
return ret;
|
||||
}
|
||||
|
||||
@@ -357,7 +362,7 @@ BlinkM::probe()
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
BlinkM::ioctl(device::file_t *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
int ret = ENOTTY;
|
||||
|
||||
@@ -942,6 +947,10 @@ blinkm_main(int argc, char *argv[])
|
||||
|
||||
int x;
|
||||
|
||||
if (argc < 2) {
|
||||
blinkm_usage();
|
||||
return 1;
|
||||
}
|
||||
for (x = 1; x < argc; x++) {
|
||||
if (strcmp(argv[x], "-b") == 0 || strcmp(argv[x], "--bus") == 0) {
|
||||
if (argc > x + 1) {
|
||||
@@ -958,38 +967,43 @@ blinkm_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
if (g_blinkm != nullptr)
|
||||
errx(1, "already started");
|
||||
if (g_blinkm != nullptr) {
|
||||
warnx("already started");
|
||||
return 1;
|
||||
}
|
||||
|
||||
g_blinkm = new BlinkM(i2cdevice, blinkmadr);
|
||||
|
||||
if (g_blinkm == nullptr)
|
||||
errx(1, "new failed");
|
||||
if (g_blinkm == nullptr) {
|
||||
warnx("new failed");
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (OK != g_blinkm->init()) {
|
||||
delete g_blinkm;
|
||||
g_blinkm = nullptr;
|
||||
errx(1, "no BlinkM found");
|
||||
warnx("init failed");
|
||||
return 1;
|
||||
}
|
||||
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
if (g_blinkm == nullptr) {
|
||||
fprintf(stderr, "not started\n");
|
||||
blinkm_usage();
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "systemstate")) {
|
||||
g_blinkm->setMode(1);
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "ledoff")) {
|
||||
g_blinkm->setMode(0);
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
@@ -997,18 +1011,22 @@ blinkm_main(int argc, char *argv[])
|
||||
for (unsigned i = 0; BlinkM::script_names[i] != nullptr; i++)
|
||||
fprintf(stderr, " %s\n", BlinkM::script_names[i]);
|
||||
fprintf(stderr, " <html color number>\n");
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* things that require access to the device */
|
||||
int fd = open(BLINKM0_DEVICE_PATH, 0);
|
||||
if (fd < 0)
|
||||
err(1, "can't open BlinkM device");
|
||||
int fd = px4_open(BLINKM0_DEVICE_PATH, 0);
|
||||
if (fd < 0) {
|
||||
warn("can't open BlinkM device");
|
||||
return 1;
|
||||
}
|
||||
|
||||
g_blinkm->setMode(0);
|
||||
if (ioctl(fd, BLINKM_PLAY_SCRIPT_NAMED, (unsigned long)argv[1]) == OK)
|
||||
exit(0);
|
||||
if (px4_ioctl(fd, BLINKM_PLAY_SCRIPT_NAMED, (unsigned long)argv[1]) == OK)
|
||||
return 0;
|
||||
|
||||
px4_close(fd);
|
||||
|
||||
blinkm_usage();
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -36,7 +36,7 @@
|
||||
* Driver for the Bosch BMA 180 MEMS accelerometer connected via SPI.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
||||
@@ -45,7 +45,7 @@
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
* AeroCore LED backend.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
|
||||
@@ -41,7 +41,7 @@
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
@@ -43,7 +43,7 @@
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
@@ -43,7 +43,7 @@
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
@@ -41,7 +41,7 @@
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
@@ -45,7 +45,7 @@
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
* PX4FMU LED backend.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
|
||||
@@ -41,7 +41,7 @@
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
@@ -41,7 +41,7 @@
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
||||
@@ -43,7 +43,7 @@
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
@@ -45,7 +45,7 @@
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
* PX4FMU LED backend.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
|
||||
@@ -41,7 +41,7 @@
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
@@ -41,7 +41,7 @@
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
@@ -41,7 +41,7 @@
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
||||
@@ -43,7 +43,7 @@
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
@@ -45,7 +45,7 @@
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
|
||||
@@ -43,7 +43,7 @@
|
||||
* Included Files
|
||||
******************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
@@ -45,7 +45,7 @@
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
|
||||
+24
-24
@@ -60,13 +60,13 @@ static const unsigned pollset_increment = 0;
|
||||
* The standard NuttX operation dispatch table can't call C++ member functions
|
||||
* directly, so we have to bounce them through this dispatch table.
|
||||
*/
|
||||
static int cdev_open(struct file *filp);
|
||||
static int cdev_close(struct file *filp);
|
||||
static ssize_t cdev_read(struct file *filp, char *buffer, size_t buflen);
|
||||
static ssize_t cdev_write(struct file *filp, const char *buffer, size_t buflen);
|
||||
static off_t cdev_seek(struct file *filp, off_t offset, int whence);
|
||||
static int cdev_ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
static int cdev_poll(struct file *filp, struct pollfd *fds, bool setup);
|
||||
static int cdev_open(file_t *filp);
|
||||
static int cdev_close(file_t *filp);
|
||||
static ssize_t cdev_read(file_t *filp, char *buffer, size_t buflen);
|
||||
static ssize_t cdev_write(file_t *filp, const char *buffer, size_t buflen);
|
||||
static off_t cdev_seek(file_t *filp, off_t offset, int whence);
|
||||
static int cdev_ioctl(file_t *filp, int cmd, unsigned long arg);
|
||||
static int cdev_poll(file_t *filp, px4_pollfd_struct_t *fds, bool setup);
|
||||
|
||||
/**
|
||||
* Character device indirection table.
|
||||
@@ -169,7 +169,7 @@ out:
|
||||
* Default implementations of the character device interface
|
||||
*/
|
||||
int
|
||||
CDev::open(struct file *filp)
|
||||
CDev::open(file_t *filp)
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
@@ -192,13 +192,13 @@ CDev::open(struct file *filp)
|
||||
}
|
||||
|
||||
int
|
||||
CDev::open_first(struct file *filp)
|
||||
CDev::open_first(file_t *filp)
|
||||
{
|
||||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::close(struct file *filp)
|
||||
CDev::close(file_t *filp)
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
@@ -222,31 +222,31 @@ CDev::close(struct file *filp)
|
||||
}
|
||||
|
||||
int
|
||||
CDev::close_last(struct file *filp)
|
||||
CDev::close_last(file_t *filp)
|
||||
{
|
||||
return OK;
|
||||
}
|
||||
|
||||
ssize_t
|
||||
CDev::read(struct file *filp, char *buffer, size_t buflen)
|
||||
CDev::read(file_t *filp, char *buffer, size_t buflen)
|
||||
{
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
ssize_t
|
||||
CDev::write(struct file *filp, const char *buffer, size_t buflen)
|
||||
CDev::write(file_t *filp, const char *buffer, size_t buflen)
|
||||
{
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
off_t
|
||||
CDev::seek(struct file *filp, off_t offset, int whence)
|
||||
CDev::seek(file_t *filp, off_t offset, int whence)
|
||||
{
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
int
|
||||
CDev::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
CDev::ioctl(file_t *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
switch (cmd) {
|
||||
|
||||
@@ -275,7 +275,7 @@ CDev::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
}
|
||||
|
||||
int
|
||||
CDev::poll(struct file *filp, struct pollfd *fds, bool setup)
|
||||
CDev::poll(file_t *filp, struct pollfd *fds, bool setup)
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
@@ -347,7 +347,7 @@ CDev::poll_notify_one(struct pollfd *fds, pollevent_t events)
|
||||
}
|
||||
|
||||
pollevent_t
|
||||
CDev::poll_state(struct file *filp)
|
||||
CDev::poll_state(file_t *filp)
|
||||
{
|
||||
/* by default, no poll events to report */
|
||||
return 0;
|
||||
@@ -389,7 +389,7 @@ CDev::remove_poll_waiter(struct pollfd *fds)
|
||||
}
|
||||
|
||||
static int
|
||||
cdev_open(struct file *filp)
|
||||
cdev_open(file_t *filp)
|
||||
{
|
||||
CDev *cdev = (CDev *)(filp->f_inode->i_private);
|
||||
|
||||
@@ -397,7 +397,7 @@ cdev_open(struct file *filp)
|
||||
}
|
||||
|
||||
static int
|
||||
cdev_close(struct file *filp)
|
||||
cdev_close(file_t *filp)
|
||||
{
|
||||
CDev *cdev = (CDev *)(filp->f_inode->i_private);
|
||||
|
||||
@@ -405,7 +405,7 @@ cdev_close(struct file *filp)
|
||||
}
|
||||
|
||||
static ssize_t
|
||||
cdev_read(struct file *filp, char *buffer, size_t buflen)
|
||||
cdev_read(file_t *filp, char *buffer, size_t buflen)
|
||||
{
|
||||
CDev *cdev = (CDev *)(filp->f_inode->i_private);
|
||||
|
||||
@@ -413,7 +413,7 @@ cdev_read(struct file *filp, char *buffer, size_t buflen)
|
||||
}
|
||||
|
||||
static ssize_t
|
||||
cdev_write(struct file *filp, const char *buffer, size_t buflen)
|
||||
cdev_write(file_t *filp, const char *buffer, size_t buflen)
|
||||
{
|
||||
CDev *cdev = (CDev *)(filp->f_inode->i_private);
|
||||
|
||||
@@ -421,7 +421,7 @@ cdev_write(struct file *filp, const char *buffer, size_t buflen)
|
||||
}
|
||||
|
||||
static off_t
|
||||
cdev_seek(struct file *filp, off_t offset, int whence)
|
||||
cdev_seek(file_t *filp, off_t offset, int whence)
|
||||
{
|
||||
CDev *cdev = (CDev *)(filp->f_inode->i_private);
|
||||
|
||||
@@ -429,7 +429,7 @@ cdev_seek(struct file *filp, off_t offset, int whence)
|
||||
}
|
||||
|
||||
static int
|
||||
cdev_ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
cdev_ioctl(file_t *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
CDev *cdev = (CDev *)(filp->f_inode->i_private);
|
||||
|
||||
@@ -437,7 +437,7 @@ cdev_ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
}
|
||||
|
||||
static int
|
||||
cdev_poll(struct file *filp, struct pollfd *fds, bool setup)
|
||||
cdev_poll(file_t *filp, px4_pollfd_struct_t *fds, bool setup)
|
||||
{
|
||||
CDev *cdev = (CDev *)(filp->f_inode->i_private);
|
||||
|
||||
|
||||
+6
-525
@@ -31,530 +31,11 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file device.h
|
||||
*
|
||||
* Definitions for the generic base classes in the device framework.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#ifndef _DEVICE_DEVICE_H
|
||||
#define _DEVICE_DEVICE_H
|
||||
#ifdef __PX4_NUTTX
|
||||
#include "device_nuttx.h"
|
||||
#elif defined (__PX4_POSIX)
|
||||
#include "vdev.h"
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Includes here should only cover the needs of the framework definitions.
|
||||
*/
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <stdbool.h>
|
||||
#include <stddef.h>
|
||||
#include <stdint.h>
|
||||
#include <poll.h>
|
||||
|
||||
#include <nuttx/fs/fs.h>
|
||||
|
||||
/**
|
||||
* Namespace encapsulating all device framework classes, functions and data.
|
||||
*/
|
||||
namespace device __EXPORT
|
||||
{
|
||||
|
||||
/**
|
||||
* Fundamental base class for all device drivers.
|
||||
*
|
||||
* This class handles the basic "being a driver" things, including
|
||||
* interrupt registration and dispatch.
|
||||
*/
|
||||
class __EXPORT Device
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Destructor.
|
||||
*
|
||||
* Public so that anonymous devices can be destroyed.
|
||||
*/
|
||||
virtual ~Device();
|
||||
|
||||
/**
|
||||
* Interrupt handler.
|
||||
*/
|
||||
virtual void interrupt(void *ctx); /**< interrupt handler */
|
||||
|
||||
/*
|
||||
* Direct access methods.
|
||||
*/
|
||||
|
||||
/**
|
||||
* Initialise the driver and make it ready for use.
|
||||
*
|
||||
* @return OK if the driver initialized OK, negative errno otherwise;
|
||||
*/
|
||||
virtual int init();
|
||||
|
||||
/**
|
||||
* Read directly from the device.
|
||||
*
|
||||
* The actual size of each unit quantity is device-specific.
|
||||
*
|
||||
* @param offset The device address at which to start reading
|
||||
* @param data The buffer into which the read values should be placed.
|
||||
* @param count The number of items to read.
|
||||
* @return The number of items read on success, negative errno otherwise.
|
||||
*/
|
||||
virtual int read(unsigned address, void *data, unsigned count);
|
||||
|
||||
/**
|
||||
* Write directly to the device.
|
||||
*
|
||||
* The actual size of each unit quantity is device-specific.
|
||||
*
|
||||
* @param address The device address at which to start writing.
|
||||
* @param data The buffer from which values should be read.
|
||||
* @param count The number of items to write.
|
||||
* @return The number of items written on success, negative errno otherwise.
|
||||
*/
|
||||
virtual int write(unsigned address, void *data, unsigned count);
|
||||
|
||||
/**
|
||||
* Perform a device-specific operation.
|
||||
*
|
||||
* @param operation The operation to perform.
|
||||
* @param arg An argument to the operation.
|
||||
* @return Negative errno on error, OK or positive value on success.
|
||||
*/
|
||||
virtual int ioctl(unsigned operation, unsigned &arg);
|
||||
|
||||
/*
|
||||
device bus types for DEVID
|
||||
*/
|
||||
enum DeviceBusType {
|
||||
DeviceBusType_UNKNOWN = 0,
|
||||
DeviceBusType_I2C = 1,
|
||||
DeviceBusType_SPI = 2,
|
||||
DeviceBusType_UAVCAN = 3,
|
||||
};
|
||||
|
||||
/*
|
||||
broken out device elements. The bitfields are used to keep
|
||||
the overall value small enough to fit in a float accurately,
|
||||
which makes it possible to transport over the MAVLink
|
||||
parameter protocol without loss of information.
|
||||
*/
|
||||
struct DeviceStructure {
|
||||
enum DeviceBusType bus_type:3;
|
||||
uint8_t bus:5; // which instance of the bus type
|
||||
uint8_t address; // address on the bus (eg. I2C address)
|
||||
uint8_t devtype; // device class specific device type
|
||||
};
|
||||
|
||||
union DeviceId {
|
||||
struct DeviceStructure devid_s;
|
||||
uint32_t devid;
|
||||
};
|
||||
|
||||
protected:
|
||||
const char *_name; /**< driver name */
|
||||
bool _debug_enabled; /**< if true, debug messages are printed */
|
||||
union DeviceId _device_id; /**< device identifier information */
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param irq Interrupt assigned to the device.
|
||||
*/
|
||||
Device(const char *name,
|
||||
int irq = 0);
|
||||
|
||||
/**
|
||||
* Enable the device interrupt
|
||||
*/
|
||||
void interrupt_enable();
|
||||
|
||||
/**
|
||||
* Disable the device interrupt
|
||||
*/
|
||||
void interrupt_disable();
|
||||
|
||||
/**
|
||||
* Take the driver lock.
|
||||
*
|
||||
* Each driver instance has its own lock/semaphore.
|
||||
*
|
||||
* Note that we must loop as the wait may be interrupted by a signal.
|
||||
*/
|
||||
void lock() {
|
||||
do {} while (sem_wait(&_lock) != 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Release the driver lock.
|
||||
*/
|
||||
void unlock() {
|
||||
sem_post(&_lock);
|
||||
}
|
||||
|
||||
/**
|
||||
* Log a message.
|
||||
*
|
||||
* The message is prefixed with the driver name, and followed
|
||||
* by a newline.
|
||||
*/
|
||||
void log(const char *fmt, ...);
|
||||
|
||||
/**
|
||||
* Print a debug message.
|
||||
*
|
||||
* The message is prefixed with the driver name, and followed
|
||||
* by a newline.
|
||||
*/
|
||||
void debug(const char *fmt, ...);
|
||||
|
||||
private:
|
||||
int _irq;
|
||||
bool _irq_attached;
|
||||
sem_t _lock;
|
||||
|
||||
/** disable copy construction for this and all subclasses */
|
||||
Device(const Device &);
|
||||
|
||||
/** disable assignment for this and all subclasses */
|
||||
Device &operator = (const Device &);
|
||||
|
||||
/**
|
||||
* Register ourselves as a handler for an interrupt
|
||||
*
|
||||
* @param irq The interrupt to claim
|
||||
* @return OK if the interrupt was registered
|
||||
*/
|
||||
int dev_register_interrupt(int irq);
|
||||
|
||||
/**
|
||||
* Unregister ourselves as a handler for any interrupt
|
||||
*/
|
||||
void dev_unregister_interrupt();
|
||||
|
||||
/**
|
||||
* Interrupt dispatcher
|
||||
*
|
||||
* @param irq The interrupt that has been triggered.
|
||||
* @param context Pointer to the interrupted context.
|
||||
*/
|
||||
static void dev_interrupt(int irq, void *context);
|
||||
|
||||
};
|
||||
|
||||
/**
|
||||
* Abstract class for any character device
|
||||
*/
|
||||
class __EXPORT CDev : public Device
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param devname Device node name
|
||||
* @param irq Interrupt assigned to the device
|
||||
*/
|
||||
CDev(const char *name, const char *devname, int irq = 0);
|
||||
|
||||
/**
|
||||
* Destructor
|
||||
*/
|
||||
virtual ~CDev();
|
||||
|
||||
virtual int init();
|
||||
|
||||
/**
|
||||
* Handle an open of the device.
|
||||
*
|
||||
* This function is called for every open of the device. The default
|
||||
* implementation maintains _open_count and always returns OK.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @return OK if the open is allowed, -errno otherwise.
|
||||
*/
|
||||
virtual int open(struct file *filp);
|
||||
|
||||
/**
|
||||
* Handle a close of the device.
|
||||
*
|
||||
* This function is called for every close of the device. The default
|
||||
* implementation maintains _open_count and returns OK as long as it is not zero.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @return OK if the close was successful, -errno otherwise.
|
||||
*/
|
||||
virtual int close(struct file *filp);
|
||||
|
||||
/**
|
||||
* Perform a read from the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @param buffer Pointer to the buffer into which data should be placed.
|
||||
* @param buflen The number of bytes to be read.
|
||||
* @return The number of bytes read or -errno otherwise.
|
||||
*/
|
||||
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
|
||||
|
||||
/**
|
||||
* Perform a write to the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @param buffer Pointer to the buffer from which data should be read.
|
||||
* @param buflen The number of bytes to be written.
|
||||
* @return The number of bytes written or -errno otherwise.
|
||||
*/
|
||||
virtual ssize_t write(struct file *filp, const char *buffer, size_t buflen);
|
||||
|
||||
/**
|
||||
* Perform a logical seek operation on the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @param offset The new file position relative to whence.
|
||||
* @param whence SEEK_OFS, SEEK_CUR or SEEK_END.
|
||||
* @return The previous offset, or -errno otherwise.
|
||||
*/
|
||||
virtual off_t seek(struct file *filp, off_t offset, int whence);
|
||||
|
||||
/**
|
||||
* Perform an ioctl operation on the device.
|
||||
*
|
||||
* The default implementation handles DIOC_GETPRIV, and otherwise
|
||||
* returns -ENOTTY. Subclasses should call the default implementation
|
||||
* for any command they do not handle themselves.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @param cmd The ioctl command value.
|
||||
* @param arg The ioctl argument value.
|
||||
* @return OK on success, or -errno otherwise.
|
||||
*/
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Perform a poll setup/teardown operation.
|
||||
*
|
||||
* This is handled internally and should not normally be overridden.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @param fds Poll descriptor being waited on.
|
||||
* @param arg True if this is establishing a request, false if
|
||||
* it is being torn down.
|
||||
* @return OK on success, or -errno otherwise.
|
||||
*/
|
||||
virtual int poll(struct file *filp, struct pollfd *fds, bool setup);
|
||||
|
||||
/**
|
||||
* Test whether the device is currently open.
|
||||
*
|
||||
* This can be used to avoid tearing down a device that is still active.
|
||||
* Note - not virtual, cannot be overridden by a subclass.
|
||||
*
|
||||
* @return True if the device is currently open.
|
||||
*/
|
||||
bool is_open() { return _open_count > 0; }
|
||||
|
||||
protected:
|
||||
/**
|
||||
* Pointer to the default cdev file operations table; useful for
|
||||
* registering clone devices etc.
|
||||
*/
|
||||
static const struct file_operations fops;
|
||||
|
||||
/**
|
||||
* Check the current state of the device for poll events from the
|
||||
* perspective of the file.
|
||||
*
|
||||
* This function is called by the default poll() implementation when
|
||||
* a poll is set up to determine whether the poll should return immediately.
|
||||
*
|
||||
* The default implementation returns no events.
|
||||
*
|
||||
* @param filp The file that's interested.
|
||||
* @return The current set of poll events.
|
||||
*/
|
||||
virtual pollevent_t poll_state(struct file *filp);
|
||||
|
||||
/**
|
||||
* Report new poll events.
|
||||
*
|
||||
* This function should be called anytime the state of the device changes
|
||||
* in a fashion that might be interesting to a poll waiter.
|
||||
*
|
||||
* @param events The new event(s) being announced.
|
||||
*/
|
||||
virtual void poll_notify(pollevent_t events);
|
||||
|
||||
/**
|
||||
* Internal implementation of poll_notify.
|
||||
*
|
||||
* @param fds A poll waiter to notify.
|
||||
* @param events The event(s) to send to the waiter.
|
||||
*/
|
||||
virtual void poll_notify_one(struct pollfd *fds, pollevent_t events);
|
||||
|
||||
/**
|
||||
* Notification of the first open.
|
||||
*
|
||||
* This function is called when the device open count transitions from zero
|
||||
* to one. The driver lock is held for the duration of the call.
|
||||
*
|
||||
* The default implementation returns OK.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @return OK if the open should proceed, -errno otherwise.
|
||||
*/
|
||||
virtual int open_first(struct file *filp);
|
||||
|
||||
/**
|
||||
* Notification of the last close.
|
||||
*
|
||||
* This function is called when the device open count transitions from
|
||||
* one to zero. The driver lock is held for the duration of the call.
|
||||
*
|
||||
* The default implementation returns OK.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @return OK if the open should return OK, -errno otherwise.
|
||||
*/
|
||||
virtual int close_last(struct file *filp);
|
||||
|
||||
/**
|
||||
* Register a class device name, automatically adding device
|
||||
* class instance suffix if need be.
|
||||
*
|
||||
* @param class_devname Device class name
|
||||
* @return class_instamce Class instance created, or -errno on failure
|
||||
*/
|
||||
virtual int register_class_devname(const char *class_devname);
|
||||
|
||||
/**
|
||||
* Register a class device name, automatically adding device
|
||||
* class instance suffix if need be.
|
||||
*
|
||||
* @param class_devname Device class name
|
||||
* @param class_instance Device class instance from register_class_devname()
|
||||
* @return OK on success, -errno otherwise
|
||||
*/
|
||||
virtual int unregister_class_devname(const char *class_devname, unsigned class_instance);
|
||||
|
||||
/**
|
||||
* Get the device name.
|
||||
*
|
||||
* @return the file system string of the device handle
|
||||
*/
|
||||
const char* get_devname() { return _devname; }
|
||||
|
||||
bool _pub_blocked; /**< true if publishing should be blocked */
|
||||
|
||||
private:
|
||||
static const unsigned _max_pollwaiters = 8;
|
||||
|
||||
const char *_devname; /**< device node name */
|
||||
bool _registered; /**< true if device name was registered */
|
||||
unsigned _open_count; /**< number of successful opens */
|
||||
|
||||
struct pollfd *_pollset[_max_pollwaiters];
|
||||
|
||||
/**
|
||||
* Store a pollwaiter in a slot where we can find it later.
|
||||
*
|
||||
* Expands the pollset as required. Must be called with the driver locked.
|
||||
*
|
||||
* @return OK, or -errno on error.
|
||||
*/
|
||||
int store_poll_waiter(struct pollfd *fds);
|
||||
|
||||
/**
|
||||
* Remove a poll waiter.
|
||||
*
|
||||
* @return OK, or -errno on error.
|
||||
*/
|
||||
int remove_poll_waiter(struct pollfd *fds);
|
||||
|
||||
/* do not allow copying this class */
|
||||
CDev(const CDev&);
|
||||
CDev operator=(const CDev&);
|
||||
};
|
||||
|
||||
/**
|
||||
* Abstract class for character device accessed via PIO
|
||||
*/
|
||||
class __EXPORT PIO : public CDev
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param devname Device node name
|
||||
* @param base Base address of the device PIO area
|
||||
* @param irq Interrupt assigned to the device (or zero if none)
|
||||
*/
|
||||
PIO(const char *name,
|
||||
const char *devname,
|
||||
uint32_t base,
|
||||
int irq = 0);
|
||||
virtual ~PIO();
|
||||
|
||||
virtual int init();
|
||||
|
||||
protected:
|
||||
|
||||
/**
|
||||
* Read a register
|
||||
*
|
||||
* @param offset Register offset in bytes from the base address.
|
||||
*/
|
||||
uint32_t reg(uint32_t offset) {
|
||||
return *(volatile uint32_t *)(_base + offset);
|
||||
}
|
||||
|
||||
/**
|
||||
* Write a register
|
||||
*
|
||||
* @param offset Register offset in bytes from the base address.
|
||||
* @param value Value to write.
|
||||
*/
|
||||
void reg(uint32_t offset, uint32_t value) {
|
||||
*(volatile uint32_t *)(_base + offset) = value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Modify a register
|
||||
*
|
||||
* Note that there is a risk of a race during the read/modify/write cycle
|
||||
* that must be taken care of by the caller.
|
||||
*
|
||||
* @param offset Register offset in bytes from the base address.
|
||||
* @param clearbits Bits to clear in the register
|
||||
* @param setbits Bits to set in the register
|
||||
*/
|
||||
void modify(uint32_t offset, uint32_t clearbits, uint32_t setbits) {
|
||||
uint32_t val = reg(offset);
|
||||
val &= ~clearbits;
|
||||
val |= setbits;
|
||||
reg(offset, val);
|
||||
}
|
||||
|
||||
private:
|
||||
uint32_t _base;
|
||||
};
|
||||
|
||||
} // namespace device
|
||||
|
||||
// class instance for primary driver of each class
|
||||
enum CLASS_DEVICE {
|
||||
CLASS_DEVICE_PRIMARY=0,
|
||||
CLASS_DEVICE_SECONDARY=1,
|
||||
CLASS_DEVICE_TERTIARY=2
|
||||
};
|
||||
|
||||
#endif /* _DEVICE_DEVICE_H */
|
||||
|
||||
@@ -0,0 +1,563 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file device_nuttx.h
|
||||
*
|
||||
* Definitions for the generic base classes in the device framework.
|
||||
*/
|
||||
|
||||
#ifndef _DEVICE_DEVICE_H
|
||||
#define _DEVICE_DEVICE_H
|
||||
|
||||
/*
|
||||
* Includes here should only cover the needs of the framework definitions.
|
||||
*/
|
||||
#include <px4_config.h>
|
||||
#include <px4_posix.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <stdbool.h>
|
||||
#include <stddef.h>
|
||||
#include <stdint.h>
|
||||
#include <poll.h>
|
||||
|
||||
#include <nuttx/fs/fs.h>
|
||||
|
||||
/**
|
||||
* Namespace encapsulating all device framework classes, functions and data.
|
||||
*/
|
||||
namespace device __EXPORT
|
||||
{
|
||||
|
||||
typedef struct file file_t;
|
||||
|
||||
/**
|
||||
* Fundamental base class for all device drivers.
|
||||
*
|
||||
* This class handles the basic "being a driver" things, including
|
||||
* interrupt registration and dispatch.
|
||||
*/
|
||||
class __EXPORT Device
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Destructor.
|
||||
*
|
||||
* Public so that anonymous devices can be destroyed.
|
||||
*/
|
||||
virtual ~Device();
|
||||
|
||||
/**
|
||||
* Interrupt handler.
|
||||
*/
|
||||
virtual void interrupt(void *ctx); /**< interrupt handler */
|
||||
|
||||
/*
|
||||
* Direct access methods.
|
||||
*/
|
||||
|
||||
/**
|
||||
* Initialise the driver and make it ready for use.
|
||||
*
|
||||
* @return OK if the driver initialized OK, negative errno otherwise;
|
||||
*/
|
||||
virtual int init();
|
||||
|
||||
/**
|
||||
* Read directly from the device.
|
||||
*
|
||||
* The actual size of each unit quantity is device-specific.
|
||||
*
|
||||
* @param offset The device address at which to start reading
|
||||
* @param data The buffer into which the read values should be placed.
|
||||
* @param count The number of items to read.
|
||||
* @return The number of items read on success, negative errno otherwise.
|
||||
*/
|
||||
virtual int read(unsigned address, void *data, unsigned count);
|
||||
|
||||
/**
|
||||
* Write directly to the device.
|
||||
*
|
||||
* The actual size of each unit quantity is device-specific.
|
||||
*
|
||||
* @param address The device address at which to start writing.
|
||||
* @param data The buffer from which values should be read.
|
||||
* @param count The number of items to write.
|
||||
* @return The number of items written on success, negative errno otherwise.
|
||||
*/
|
||||
virtual int write(unsigned address, void *data, unsigned count);
|
||||
|
||||
/**
|
||||
* Perform a device-specific operation.
|
||||
*
|
||||
* @param operation The operation to perform.
|
||||
* @param arg An argument to the operation.
|
||||
* @return Negative errno on error, OK or positive value on success.
|
||||
*/
|
||||
virtual int ioctl(unsigned operation, unsigned &arg);
|
||||
|
||||
/*
|
||||
device bus types for DEVID
|
||||
*/
|
||||
enum DeviceBusType {
|
||||
DeviceBusType_UNKNOWN = 0,
|
||||
DeviceBusType_I2C = 1,
|
||||
DeviceBusType_SPI = 2,
|
||||
DeviceBusType_UAVCAN = 3,
|
||||
};
|
||||
|
||||
/*
|
||||
broken out device elements. The bitfields are used to keep
|
||||
the overall value small enough to fit in a float accurately,
|
||||
which makes it possible to transport over the MAVLink
|
||||
parameter protocol without loss of information.
|
||||
*/
|
||||
struct DeviceStructure {
|
||||
enum DeviceBusType bus_type:3;
|
||||
uint8_t bus:5; // which instance of the bus type
|
||||
uint8_t address; // address on the bus (eg. I2C address)
|
||||
uint8_t devtype; // device class specific device type
|
||||
};
|
||||
|
||||
union DeviceId {
|
||||
struct DeviceStructure devid_s;
|
||||
uint32_t devid;
|
||||
};
|
||||
|
||||
protected:
|
||||
const char *_name; /**< driver name */
|
||||
bool _debug_enabled; /**< if true, debug messages are printed */
|
||||
union DeviceId _device_id; /**< device identifier information */
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param irq Interrupt assigned to the device.
|
||||
*/
|
||||
Device(const char *name,
|
||||
int irq = 0);
|
||||
|
||||
/**
|
||||
* Enable the device interrupt
|
||||
*/
|
||||
void interrupt_enable();
|
||||
|
||||
/**
|
||||
* Disable the device interrupt
|
||||
*/
|
||||
void interrupt_disable();
|
||||
|
||||
/**
|
||||
* Take the driver lock.
|
||||
*
|
||||
* Each driver instance has its own lock/semaphore.
|
||||
*
|
||||
* Note that we must loop as the wait may be interrupted by a signal.
|
||||
*/
|
||||
void lock() {
|
||||
do {} while (sem_wait(&_lock) != 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Release the driver lock.
|
||||
*/
|
||||
void unlock() {
|
||||
sem_post(&_lock);
|
||||
}
|
||||
|
||||
/**
|
||||
* Log a message.
|
||||
*
|
||||
* The message is prefixed with the driver name, and followed
|
||||
* by a newline.
|
||||
*/
|
||||
void log(const char *fmt, ...);
|
||||
|
||||
/**
|
||||
* Print a debug message.
|
||||
*
|
||||
* The message is prefixed with the driver name, and followed
|
||||
* by a newline.
|
||||
*/
|
||||
void debug(const char *fmt, ...);
|
||||
|
||||
private:
|
||||
int _irq;
|
||||
bool _irq_attached;
|
||||
sem_t _lock;
|
||||
|
||||
/** disable copy construction for this and all subclasses */
|
||||
Device(const Device &);
|
||||
|
||||
/** disable assignment for this and all subclasses */
|
||||
Device &operator = (const Device &);
|
||||
|
||||
/**
|
||||
* Register ourselves as a handler for an interrupt
|
||||
*
|
||||
* @param irq The interrupt to claim
|
||||
* @return OK if the interrupt was registered
|
||||
*/
|
||||
int dev_register_interrupt(int irq);
|
||||
|
||||
/**
|
||||
* Unregister ourselves as a handler for any interrupt
|
||||
*/
|
||||
void dev_unregister_interrupt();
|
||||
|
||||
/**
|
||||
* Interrupt dispatcher
|
||||
*
|
||||
* @param irq The interrupt that has been triggered.
|
||||
* @param context Pointer to the interrupted context.
|
||||
*/
|
||||
static void dev_interrupt(int irq, void *context);
|
||||
|
||||
};
|
||||
|
||||
/**
|
||||
* Abstract class for any character device
|
||||
*/
|
||||
class __EXPORT CDev : public Device
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param devname Device node name
|
||||
* @param irq Interrupt assigned to the device
|
||||
*/
|
||||
CDev(const char *name, const char *devname, int irq = 0);
|
||||
|
||||
/**
|
||||
* Destructor
|
||||
*/
|
||||
virtual ~CDev();
|
||||
|
||||
virtual int init();
|
||||
|
||||
/**
|
||||
* Handle an open of the device.
|
||||
*
|
||||
* This function is called for every open of the device. The default
|
||||
* implementation maintains _open_count and always returns OK.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @return OK if the open is allowed, -errno otherwise.
|
||||
*/
|
||||
virtual int open(file_t *filp);
|
||||
|
||||
/**
|
||||
* Handle a close of the device.
|
||||
*
|
||||
* This function is called for every close of the device. The default
|
||||
* implementation maintains _open_count and returns OK as long as it is not zero.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @return OK if the close was successful, -errno otherwise.
|
||||
*/
|
||||
virtual int close(file_t *filp);
|
||||
|
||||
/**
|
||||
* Perform a read from the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @param buffer Pointer to the buffer into which data should be placed.
|
||||
* @param buflen The number of bytes to be read.
|
||||
* @return The number of bytes read or -errno otherwise.
|
||||
*/
|
||||
virtual ssize_t read(file_t *filp, char *buffer, size_t buflen);
|
||||
|
||||
/**
|
||||
* Perform a write to the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @param buffer Pointer to the buffer from which data should be read.
|
||||
* @param buflen The number of bytes to be written.
|
||||
* @return The number of bytes written or -errno otherwise.
|
||||
*/
|
||||
virtual ssize_t write(file_t *filp, const char *buffer, size_t buflen);
|
||||
|
||||
/**
|
||||
* Perform a logical seek operation on the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @param offset The new file position relative to whence.
|
||||
* @param whence SEEK_OFS, SEEK_CUR or SEEK_END.
|
||||
* @return The previous offset, or -errno otherwise.
|
||||
*/
|
||||
virtual off_t seek(file_t *filp, off_t offset, int whence);
|
||||
|
||||
/**
|
||||
* Perform an ioctl operation on the device.
|
||||
*
|
||||
* The default implementation handles DIOC_GETPRIV, and otherwise
|
||||
* returns -ENOTTY. Subclasses should call the default implementation
|
||||
* for any command they do not handle themselves.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @param cmd The ioctl command value.
|
||||
* @param arg The ioctl argument value.
|
||||
* @return OK on success, or -errno otherwise.
|
||||
*/
|
||||
virtual int ioctl(file_t *filp, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Perform a poll setup/teardown operation.
|
||||
*
|
||||
* This is handled internally and should not normally be overridden.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @param fds Poll descriptor being waited on.
|
||||
* @param arg True if this is establishing a request, false if
|
||||
* it is being torn down.
|
||||
* @return OK on success, or -errno otherwise.
|
||||
*/
|
||||
virtual int poll(file_t *filp, struct pollfd *fds, bool setup);
|
||||
|
||||
/**
|
||||
* Test whether the device is currently open.
|
||||
*
|
||||
* This can be used to avoid tearing down a device that is still active.
|
||||
* Note - not virtual, cannot be overridden by a subclass.
|
||||
*
|
||||
* @return True if the device is currently open.
|
||||
*/
|
||||
bool is_open() { return _open_count > 0; }
|
||||
|
||||
protected:
|
||||
/**
|
||||
* Pointer to the default cdev file operations table; useful for
|
||||
* registering clone devices etc.
|
||||
*/
|
||||
static const struct file_operations fops;
|
||||
|
||||
/**
|
||||
* Check the current state of the device for poll events from the
|
||||
* perspective of the file.
|
||||
*
|
||||
* This function is called by the default poll() implementation when
|
||||
* a poll is set up to determine whether the poll should return immediately.
|
||||
*
|
||||
* The default implementation returns no events.
|
||||
*
|
||||
* @param filp The file that's interested.
|
||||
* @return The current set of poll events.
|
||||
*/
|
||||
virtual pollevent_t poll_state(file_t *filp);
|
||||
|
||||
/**
|
||||
* Report new poll events.
|
||||
*
|
||||
* This function should be called anytime the state of the device changes
|
||||
* in a fashion that might be interesting to a poll waiter.
|
||||
*
|
||||
* @param events The new event(s) being announced.
|
||||
*/
|
||||
virtual void poll_notify(pollevent_t events);
|
||||
|
||||
/**
|
||||
* Internal implementation of poll_notify.
|
||||
*
|
||||
* @param fds A poll waiter to notify.
|
||||
* @param events The event(s) to send to the waiter.
|
||||
*/
|
||||
virtual void poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events);
|
||||
|
||||
/**
|
||||
* Notification of the first open.
|
||||
*
|
||||
* This function is called when the device open count transitions from zero
|
||||
* to one. The driver lock is held for the duration of the call.
|
||||
*
|
||||
* The default implementation returns OK.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @return OK if the open should proceed, -errno otherwise.
|
||||
*/
|
||||
virtual int open_first(file_t *filp);
|
||||
|
||||
/**
|
||||
* Notification of the last close.
|
||||
*
|
||||
* This function is called when the device open count transitions from
|
||||
* one to zero. The driver lock is held for the duration of the call.
|
||||
*
|
||||
* The default implementation returns OK.
|
||||
*
|
||||
* @param filp Pointer to the NuttX file structure.
|
||||
* @return OK if the open should return OK, -errno otherwise.
|
||||
*/
|
||||
virtual int close_last(file_t *filp);
|
||||
|
||||
/**
|
||||
* Register a class device name, automatically adding device
|
||||
* class instance suffix if need be.
|
||||
*
|
||||
* @param class_devname Device class name
|
||||
* @return class_instamce Class instance created, or -errno on failure
|
||||
*/
|
||||
virtual int register_class_devname(const char *class_devname);
|
||||
|
||||
/**
|
||||
* Register a class device name, automatically adding device
|
||||
* class instance suffix if need be.
|
||||
*
|
||||
* @param class_devname Device class name
|
||||
* @param class_instance Device class instance from register_class_devname()
|
||||
* @return OK on success, -errno otherwise
|
||||
*/
|
||||
virtual int unregister_class_devname(const char *class_devname, unsigned class_instance);
|
||||
|
||||
/**
|
||||
* Get the device name.
|
||||
*
|
||||
* @return the file system string of the device handle
|
||||
*/
|
||||
const char* get_devname() { return _devname; }
|
||||
|
||||
bool _pub_blocked; /**< true if publishing should be blocked */
|
||||
|
||||
private:
|
||||
static const unsigned _max_pollwaiters = 8;
|
||||
|
||||
const char *_devname; /**< device node name */
|
||||
bool _registered; /**< true if device name was registered */
|
||||
unsigned _open_count; /**< number of successful opens */
|
||||
|
||||
struct pollfd *_pollset[_max_pollwaiters];
|
||||
|
||||
/**
|
||||
* Store a pollwaiter in a slot where we can find it later.
|
||||
*
|
||||
* Expands the pollset as required. Must be called with the driver locked.
|
||||
*
|
||||
* @return OK, or -errno on error.
|
||||
*/
|
||||
int store_poll_waiter(px4_pollfd_struct_t *fds);
|
||||
|
||||
/**
|
||||
* Remove a poll waiter.
|
||||
*
|
||||
* @return OK, or -errno on error.
|
||||
*/
|
||||
int remove_poll_waiter(struct pollfd *fds);
|
||||
|
||||
/* do not allow copying this class */
|
||||
CDev(const CDev&);
|
||||
CDev operator=(const CDev&);
|
||||
};
|
||||
|
||||
/**
|
||||
* Abstract class for character device accessed via PIO
|
||||
*/
|
||||
class __EXPORT PIO : public CDev
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param devname Device node name
|
||||
* @param base Base address of the device PIO area
|
||||
* @param irq Interrupt assigned to the device (or zero if none)
|
||||
*/
|
||||
PIO(const char *name,
|
||||
const char *devname,
|
||||
uint32_t base,
|
||||
int irq = 0);
|
||||
virtual ~PIO();
|
||||
|
||||
virtual int init();
|
||||
|
||||
protected:
|
||||
|
||||
/**
|
||||
* Read a register
|
||||
*
|
||||
* @param offset Register offset in bytes from the base address.
|
||||
*/
|
||||
uint32_t reg(uint32_t offset) {
|
||||
return *(volatile uint32_t *)(_base + offset);
|
||||
}
|
||||
|
||||
/**
|
||||
* Write a register
|
||||
*
|
||||
* @param offset Register offset in bytes from the base address.
|
||||
* @param value Value to write.
|
||||
*/
|
||||
void reg(uint32_t offset, uint32_t value) {
|
||||
*(volatile uint32_t *)(_base + offset) = value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Modify a register
|
||||
*
|
||||
* Note that there is a risk of a race during the read/modify/write cycle
|
||||
* that must be taken care of by the caller.
|
||||
*
|
||||
* @param offset Register offset in bytes from the base address.
|
||||
* @param clearbits Bits to clear in the register
|
||||
* @param setbits Bits to set in the register
|
||||
*/
|
||||
void modify(uint32_t offset, uint32_t clearbits, uint32_t setbits) {
|
||||
uint32_t val = reg(offset);
|
||||
val &= ~clearbits;
|
||||
val |= setbits;
|
||||
reg(offset, val);
|
||||
}
|
||||
|
||||
private:
|
||||
uint32_t _base;
|
||||
};
|
||||
|
||||
} // namespace device
|
||||
|
||||
// class instance for primary driver of each class
|
||||
enum CLASS_DEVICE {
|
||||
CLASS_DEVICE_PRIMARY=0,
|
||||
CLASS_DEVICE_SECONDARY=1,
|
||||
CLASS_DEVICE_TERTIARY=2
|
||||
};
|
||||
|
||||
#endif /* _DEVICE_DEVICE_H */
|
||||
@@ -0,0 +1,131 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file device.cpp
|
||||
*
|
||||
* Fundamental driver base class for the virtual device framework.
|
||||
*/
|
||||
|
||||
#include "device.h"
|
||||
|
||||
#include <px4_defines.h>
|
||||
#include <px4_posix.h>
|
||||
#include <drivers/drv_device.h>
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
|
||||
namespace device
|
||||
{
|
||||
|
||||
Device::Device(const char *name) :
|
||||
// public
|
||||
// protected
|
||||
_name(name),
|
||||
_debug_enabled(false)
|
||||
{
|
||||
sem_init(&_lock, 0, 1);
|
||||
|
||||
/* setup a default device ID. When bus_type is UNKNOWN the
|
||||
other fields are invalid */
|
||||
_device_id.devid = 0;
|
||||
_device_id.devid_s.bus_type = DeviceBusType_UNKNOWN;
|
||||
_device_id.devid_s.bus = 0;
|
||||
_device_id.devid_s.address = 0;
|
||||
_device_id.devid_s.devtype = 0;
|
||||
}
|
||||
|
||||
Device::~Device()
|
||||
{
|
||||
sem_destroy(&_lock);
|
||||
}
|
||||
|
||||
int
|
||||
Device::init()
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
Device::log(const char *fmt, ...)
|
||||
{
|
||||
va_list ap;
|
||||
|
||||
PX4_INFO("[%s] ", _name);
|
||||
va_start(ap, fmt);
|
||||
vprintf(fmt, ap);
|
||||
va_end(ap);
|
||||
printf("\n");
|
||||
fflush(stdout);
|
||||
}
|
||||
|
||||
void
|
||||
Device::debug(const char *fmt, ...)
|
||||
{
|
||||
va_list ap;
|
||||
|
||||
if (_debug_enabled) {
|
||||
printf("<%s> ", _name);
|
||||
va_start(ap, fmt);
|
||||
vprintf(fmt, ap);
|
||||
va_end(ap);
|
||||
printf("\n");
|
||||
fflush(stdout);
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
Device::dev_read(unsigned offset, void *data, unsigned count)
|
||||
{
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
int
|
||||
Device::dev_write(unsigned offset, void *data, unsigned count)
|
||||
{
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
int
|
||||
Device::dev_ioctl(unsigned operation, unsigned &arg)
|
||||
{
|
||||
switch (operation) {
|
||||
case DEVIOCGDEVICEID:
|
||||
return (int)_device_id.devid;
|
||||
}
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
} // namespace device
|
||||
+7
-121
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2015 Mark Charlebois. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -30,124 +30,10 @@
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* @file i2c.h
|
||||
*
|
||||
* Base class for devices connected via I2C.
|
||||
*/
|
||||
|
||||
#ifndef _DEVICE_I2C_H
|
||||
#define _DEVICE_I2C_H
|
||||
|
||||
#include "device.h"
|
||||
|
||||
#include <nuttx/i2c.h>
|
||||
|
||||
namespace device __EXPORT
|
||||
{
|
||||
|
||||
/**
|
||||
* Abstract class for character device on I2C
|
||||
*/
|
||||
class __EXPORT I2C : public CDev
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
/**
|
||||
* Get the address
|
||||
*/
|
||||
int16_t get_address() const { return _address; }
|
||||
|
||||
static int set_bus_clock(unsigned bus, unsigned clock_hz);
|
||||
|
||||
static unsigned int _bus_clocks[3];
|
||||
|
||||
protected:
|
||||
/**
|
||||
* The number of times a read or write operation will be retried on
|
||||
* error.
|
||||
*/
|
||||
unsigned _retries;
|
||||
|
||||
/**
|
||||
* The I2C bus number the device is attached to.
|
||||
*/
|
||||
int _bus;
|
||||
|
||||
/**
|
||||
* @ Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param devname Device node name
|
||||
* @param bus I2C bus on which the device lives
|
||||
* @param address I2C bus address, or zero if set_address will be used
|
||||
* @param frequency I2C bus frequency for the device (currently not used)
|
||||
* @param irq Interrupt assigned to the device (or zero if none)
|
||||
*/
|
||||
I2C(const char *name,
|
||||
const char *devname,
|
||||
int bus,
|
||||
uint16_t address,
|
||||
uint32_t frequency,
|
||||
int irq = 0);
|
||||
virtual ~I2C();
|
||||
|
||||
virtual int init();
|
||||
|
||||
/**
|
||||
* Check for the presence of the device on the bus.
|
||||
*/
|
||||
virtual int probe();
|
||||
|
||||
/**
|
||||
* Perform an I2C transaction to the device.
|
||||
*
|
||||
* At least one of send_len and recv_len must be non-zero.
|
||||
*
|
||||
* @param send Pointer to bytes to send.
|
||||
* @param send_len Number of bytes to send.
|
||||
* @param recv Pointer to buffer for bytes received.
|
||||
* @param recv_len Number of bytes to receive.
|
||||
* @return OK if the transfer was successful, -errno
|
||||
* otherwise.
|
||||
*/
|
||||
int transfer(const uint8_t *send, unsigned send_len,
|
||||
uint8_t *recv, unsigned recv_len);
|
||||
|
||||
/**
|
||||
* Perform a multi-part I2C transaction to the device.
|
||||
*
|
||||
* @param msgv An I2C message vector.
|
||||
* @param msgs The number of entries in the message vector.
|
||||
* @return OK if the transfer was successful, -errno
|
||||
* otherwise.
|
||||
*/
|
||||
int transfer(i2c_msg_s *msgv, unsigned msgs);
|
||||
|
||||
/**
|
||||
* Change the bus address.
|
||||
*
|
||||
* Most often useful during probe() when the driver is testing
|
||||
* several possible bus addresses.
|
||||
*
|
||||
* @param address The new bus address to set.
|
||||
*/
|
||||
void set_address(uint16_t address) {
|
||||
_address = address;
|
||||
_device_id.devid_s.address = _address;
|
||||
}
|
||||
|
||||
private:
|
||||
uint16_t _address;
|
||||
uint32_t _frequency;
|
||||
struct i2c_dev_s *_dev;
|
||||
|
||||
I2C(const device::I2C &);
|
||||
I2C operator=(const device::I2C &);
|
||||
};
|
||||
|
||||
} // namespace device
|
||||
|
||||
#endif /* _DEVICE_I2C_H */
|
||||
#ifdef __PX4_NUTTX
|
||||
#include "i2c_nuttx.h"
|
||||
#else
|
||||
#include "i2c_posix.h"
|
||||
#endif
|
||||
|
||||
@@ -0,0 +1,153 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 i2c.h
|
||||
*
|
||||
* Base class for devices connected via I2C.
|
||||
*/
|
||||
|
||||
#ifndef _DEVICE_I2C_H
|
||||
#define _DEVICE_I2C_H
|
||||
|
||||
#include "device.h"
|
||||
|
||||
#include <px4_i2c.h>
|
||||
|
||||
namespace device __EXPORT
|
||||
{
|
||||
|
||||
/**
|
||||
* Abstract class for character device on I2C
|
||||
*/
|
||||
class __EXPORT I2C : public CDev
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
/**
|
||||
* Get the address
|
||||
*/
|
||||
int16_t get_address() const { return _address; }
|
||||
|
||||
static int set_bus_clock(unsigned bus, unsigned clock_hz);
|
||||
|
||||
static unsigned int _bus_clocks[3];
|
||||
|
||||
protected:
|
||||
/**
|
||||
* The number of times a read or write operation will be retried on
|
||||
* error.
|
||||
*/
|
||||
unsigned _retries;
|
||||
|
||||
/**
|
||||
* The I2C bus number the device is attached to.
|
||||
*/
|
||||
int _bus;
|
||||
|
||||
/**
|
||||
* @ Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param devname Device node name
|
||||
* @param bus I2C bus on which the device lives
|
||||
* @param address I2C bus address, or zero if set_address will be used
|
||||
* @param frequency I2C bus frequency for the device (currently not used)
|
||||
* @param irq Interrupt assigned to the device (or zero if none)
|
||||
*/
|
||||
I2C(const char *name,
|
||||
const char *devname,
|
||||
int bus,
|
||||
uint16_t address,
|
||||
uint32_t frequency,
|
||||
int irq = 0);
|
||||
virtual ~I2C();
|
||||
|
||||
virtual int init();
|
||||
|
||||
/**
|
||||
* Check for the presence of the device on the bus.
|
||||
*/
|
||||
virtual int probe();
|
||||
|
||||
/**
|
||||
* Perform an I2C transaction to the device.
|
||||
*
|
||||
* At least one of send_len and recv_len must be non-zero.
|
||||
*
|
||||
* @param send Pointer to bytes to send.
|
||||
* @param send_len Number of bytes to send.
|
||||
* @param recv Pointer to buffer for bytes received.
|
||||
* @param recv_len Number of bytes to receive.
|
||||
* @return OK if the transfer was successful, -errno
|
||||
* otherwise.
|
||||
*/
|
||||
int transfer(const uint8_t *send, unsigned send_len,
|
||||
uint8_t *recv, unsigned recv_len);
|
||||
|
||||
/**
|
||||
* Perform a multi-part I2C transaction to the device.
|
||||
*
|
||||
* @param msgv An I2C message vector.
|
||||
* @param msgs The number of entries in the message vector.
|
||||
* @return OK if the transfer was successful, -errno
|
||||
* otherwise.
|
||||
*/
|
||||
int transfer(px4_i2c_msg_t *msgv, unsigned msgs);
|
||||
|
||||
/**
|
||||
* Change the bus address.
|
||||
*
|
||||
* Most often useful during probe() when the driver is testing
|
||||
* several possible bus addresses.
|
||||
*
|
||||
* @param address The new bus address to set.
|
||||
*/
|
||||
void set_address(uint16_t address) {
|
||||
_address = address;
|
||||
_device_id.devid_s.address = _address;
|
||||
}
|
||||
|
||||
private:
|
||||
uint16_t _address;
|
||||
uint32_t _frequency;
|
||||
px4_i2c_dev_t *_dev;
|
||||
|
||||
I2C(const device::I2C &);
|
||||
I2C operator=(const device::I2C &);
|
||||
};
|
||||
|
||||
} // namespace device
|
||||
|
||||
#endif /* _DEVICE_I2C_H */
|
||||
@@ -0,0 +1,263 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2015 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 i2c.cpp
|
||||
*
|
||||
* Base class for devices attached via the I2C bus.
|
||||
*
|
||||
* @todo Bus frequency changes; currently we do nothing with the value
|
||||
* that is supplied. Should we just depend on the bus knowing?
|
||||
*/
|
||||
|
||||
#include "i2c.h"
|
||||
#ifdef __PX4_LINUX
|
||||
#include <linux/i2c.h>
|
||||
#include <linux/i2c-dev.h>
|
||||
#endif
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
#define PX4_SIMULATE_I2C 1
|
||||
static int simulate = PX4_SIMULATE_I2C;
|
||||
|
||||
namespace device
|
||||
{
|
||||
|
||||
I2C::I2C(const char *name,
|
||||
const char *devname,
|
||||
int bus,
|
||||
uint16_t address) :
|
||||
// base class
|
||||
VDev(name, devname),
|
||||
// public
|
||||
// protected
|
||||
_retries(0),
|
||||
// private
|
||||
_bus(bus),
|
||||
_address(address),
|
||||
_fd(-1)
|
||||
{
|
||||
warnx("I2C::I2C name = %s devname = %s", name, devname);
|
||||
// fill in _device_id fields for a I2C device
|
||||
_device_id.devid_s.bus_type = DeviceBusType_I2C;
|
||||
_device_id.devid_s.bus = bus;
|
||||
_device_id.devid_s.address = address;
|
||||
// devtype needs to be filled in by the driver
|
||||
_device_id.devid_s.devtype = 0;
|
||||
}
|
||||
|
||||
I2C::~I2C()
|
||||
{
|
||||
if (_fd >= 0) {
|
||||
::close(_fd);
|
||||
_fd = -1;
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
I2C::init()
|
||||
{
|
||||
int ret = PX4_OK;
|
||||
|
||||
// Assume the driver set the desired bus frequency. There is no standard
|
||||
// way to set it from user space.
|
||||
|
||||
// do base class init, which will create device node, etc
|
||||
ret = VDev::init();
|
||||
|
||||
if (ret != PX4_OK) {
|
||||
debug("VDev::init failed");
|
||||
return ret;
|
||||
}
|
||||
|
||||
_fd = px4_open(get_devname(), PX4_F_RDONLY | PX4_F_WRONLY);
|
||||
if (_fd < 0) {
|
||||
debug("px4_open failed of device %s", get_devname());
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
#ifdef __PX4_QURT
|
||||
simulate = true;
|
||||
#endif
|
||||
|
||||
if (simulate) {
|
||||
_fd = 10000;
|
||||
}
|
||||
else {
|
||||
// Open the actual I2C device and map to the virtual dev name
|
||||
_fd = ::open(get_devname(), O_RDWR);
|
||||
if (_fd < 0) {
|
||||
warnx("could not open %s", get_devname());
|
||||
px4_errno = errno;
|
||||
return PX4_ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
I2C::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len)
|
||||
{
|
||||
struct i2c_msg msgv[2];
|
||||
unsigned msgs;
|
||||
struct i2c_rdwr_ioctl_data packets;
|
||||
int ret;
|
||||
unsigned retry_count = 0;
|
||||
|
||||
if (_fd < 0) {
|
||||
warnx("I2C device not opened");
|
||||
return 1;
|
||||
}
|
||||
|
||||
do {
|
||||
// debug("transfer out %p/%u in %p/%u", send, send_len, recv, recv_len);
|
||||
msgs = 0;
|
||||
|
||||
if (send_len > 0) {
|
||||
msgv[msgs].addr = _address;
|
||||
msgv[msgs].flags = 0;
|
||||
msgv[msgs].buf = const_cast<uint8_t *>(send);
|
||||
msgv[msgs].len = send_len;
|
||||
msgs++;
|
||||
}
|
||||
|
||||
if (recv_len > 0) {
|
||||
msgv[msgs].addr = _address;
|
||||
msgv[msgs].flags = I2C_M_READ;
|
||||
msgv[msgs].buf = recv;
|
||||
msgv[msgs].len = recv_len;
|
||||
msgs++;
|
||||
}
|
||||
|
||||
if (msgs == 0)
|
||||
return -EINVAL;
|
||||
|
||||
packets.msgs = msgv;
|
||||
packets.nmsgs = msgs;
|
||||
|
||||
if (simulate) {
|
||||
//warnx("I2C SIM: transfer_4 on %s", get_devname());
|
||||
ret = PX4_OK;
|
||||
}
|
||||
else {
|
||||
ret = ::ioctl(_fd, I2C_RDWR, (unsigned long)&packets);
|
||||
if (ret < 0) {
|
||||
warnx("I2C transfer failed");
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
/* success */
|
||||
if (ret == PX4_OK)
|
||||
break;
|
||||
|
||||
} while (retry_count++ < _retries);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
I2C::transfer(struct i2c_msg *msgv, unsigned msgs)
|
||||
{
|
||||
struct i2c_rdwr_ioctl_data packets;
|
||||
int ret;
|
||||
unsigned retry_count = 0;
|
||||
|
||||
/* force the device address into the message vector */
|
||||
for (unsigned i = 0; i < msgs; i++)
|
||||
msgv[i].addr = _address;
|
||||
|
||||
do {
|
||||
packets.msgs = msgv;
|
||||
packets.nmsgs = msgs;
|
||||
|
||||
if (simulate) {
|
||||
warnx("I2C SIM: transfer_2 on %s", get_devname());
|
||||
ret = PX4_OK;
|
||||
}
|
||||
else {
|
||||
ret = ::ioctl(_fd, I2C_RDWR, (unsigned long)&packets);
|
||||
}
|
||||
if (ret < 0) {
|
||||
warnx("I2C transfer failed");
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* success */
|
||||
if (ret == PX4_OK)
|
||||
break;
|
||||
|
||||
} while (retry_count++ < _retries);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int I2C::ioctl(device::file_t *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
//struct i2c_rdwr_ioctl_data *packets = (i2c_rdwr_ioctl_data *)(void *)arg;
|
||||
|
||||
switch (cmd) {
|
||||
case I2C_RDWR:
|
||||
warnx("Use I2C::transfer, not ioctl");
|
||||
return 0;
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return VDev::ioctl(filp, cmd, arg);
|
||||
}
|
||||
}
|
||||
|
||||
ssize_t I2C::read(file_t *filp, char *buffer, size_t buflen)
|
||||
{
|
||||
if (simulate) {
|
||||
// FIXME no idea what this should be
|
||||
warnx ("2C SIM I2C::read");
|
||||
return 0;
|
||||
}
|
||||
|
||||
return ::read(_fd, buffer, buflen);
|
||||
}
|
||||
|
||||
ssize_t I2C::write(file_t *filp, const char *buffer, size_t buflen)
|
||||
{
|
||||
if (simulate) {
|
||||
warnx ("2C SIM I2C::write");
|
||||
return buflen;
|
||||
}
|
||||
|
||||
return ::write(_fd, buffer, buflen);
|
||||
}
|
||||
|
||||
} // namespace device
|
||||
@@ -0,0 +1,136 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 i2c.h
|
||||
*
|
||||
* Base class for devices connected via I2C.
|
||||
*/
|
||||
|
||||
#ifndef _DEVICE_I2C_H
|
||||
#define _DEVICE_I2C_H
|
||||
|
||||
#include "vdev.h"
|
||||
|
||||
#include <px4_i2c.h>
|
||||
#ifdef __PX4_LINUX
|
||||
#include <linux/i2c.h>
|
||||
#include <linux/i2c-dev.h>
|
||||
#endif
|
||||
#include <string>
|
||||
|
||||
namespace device __EXPORT
|
||||
{
|
||||
|
||||
/**
|
||||
* Abstract class for character device on I2C
|
||||
*/
|
||||
class __EXPORT I2C : public VDev
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
/**
|
||||
* Get the address
|
||||
*/
|
||||
int16_t get_address() const { return _address; }
|
||||
|
||||
protected:
|
||||
/**
|
||||
* The number of times a read or write operation will be retried on
|
||||
* error.
|
||||
*/
|
||||
unsigned _retries;
|
||||
|
||||
/**
|
||||
* The I2C bus number the device is attached to.
|
||||
*/
|
||||
int _bus;
|
||||
|
||||
/**
|
||||
* @ Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param devname Device node name
|
||||
* @param bus I2C bus on which the device lives
|
||||
* @param address I2C bus address, or zero if set_address will be used
|
||||
*/
|
||||
I2C(const char *name,
|
||||
const char *devname,
|
||||
int bus,
|
||||
uint16_t address);
|
||||
virtual ~I2C();
|
||||
|
||||
virtual int init();
|
||||
|
||||
virtual ssize_t read(file_t *handlep, char *buffer, size_t buflen);
|
||||
virtual ssize_t write(file_t *handlep, const char *buffer, size_t buflen);
|
||||
virtual int ioctl(file_t *handlep, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Perform an I2C transaction to the device.
|
||||
*
|
||||
* At least one of send_len and recv_len must be non-zero.
|
||||
*
|
||||
* @param send Pointer to bytes to send.
|
||||
* @param send_len Number of bytes to send.
|
||||
* @param recv Pointer to buffer for bytes received.
|
||||
* @param recv_len Number of bytes to receive.
|
||||
* @return OK if the transfer was successful, -errno
|
||||
* otherwise.
|
||||
*/
|
||||
int transfer(const uint8_t *send, unsigned send_len,
|
||||
uint8_t *recv, unsigned recv_len);
|
||||
|
||||
/**
|
||||
* Perform a multi-part I2C transaction to the device.
|
||||
*
|
||||
* @param msgv An I2C message vector.
|
||||
* @param msgs The number of entries in the message vector.
|
||||
* @return OK if the transfer was successful, -errno
|
||||
* otherwise.
|
||||
*/
|
||||
int transfer(struct i2c_msg *msgv, unsigned msgs);
|
||||
|
||||
private:
|
||||
uint16_t _address;
|
||||
int _fd;
|
||||
std::string _dname;
|
||||
|
||||
I2C(const device::I2C&);
|
||||
I2C operator=(const device::I2C&);
|
||||
};
|
||||
|
||||
} // namespace device
|
||||
|
||||
#endif /* _DEVICE_I2C_H */
|
||||
@@ -35,8 +35,20 @@
|
||||
# Build the device driver framework.
|
||||
#
|
||||
|
||||
SRCS = cdev.cpp \
|
||||
device.cpp \
|
||||
i2c.cpp \
|
||||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
SRCS = \
|
||||
device_nuttx.cpp \
|
||||
cdev.cpp \
|
||||
i2c_nuttx.cpp \
|
||||
pio.cpp \
|
||||
spi.cpp
|
||||
spi.cpp
|
||||
else
|
||||
SRCS = \
|
||||
device_posix.cpp \
|
||||
vdev.cpp \
|
||||
vfile.cpp \
|
||||
vdev_posix.cpp \
|
||||
i2c_posix.cpp \
|
||||
sim.cpp \
|
||||
ringbuffer.cpp
|
||||
endif
|
||||
|
||||
@@ -0,0 +1,400 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 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 ringbuffer.cpp
|
||||
*
|
||||
* A flexible ringbuffer class.
|
||||
*/
|
||||
|
||||
#include "ringbuffer.h"
|
||||
#include <string.h>
|
||||
|
||||
RingBuffer::RingBuffer(unsigned num_items, size_t item_size) :
|
||||
_num_items(num_items),
|
||||
_item_size(item_size),
|
||||
_buf(new char[(_num_items+1) * item_size]),
|
||||
_head(_num_items),
|
||||
_tail(_num_items)
|
||||
{}
|
||||
|
||||
RingBuffer::~RingBuffer()
|
||||
{
|
||||
if (_buf != nullptr)
|
||||
delete[] _buf;
|
||||
}
|
||||
|
||||
unsigned
|
||||
RingBuffer::_next(unsigned index)
|
||||
{
|
||||
return (0 == index) ? _num_items : (index - 1);
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::empty()
|
||||
{
|
||||
return _tail == _head;
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::full()
|
||||
{
|
||||
return _next(_head) == _tail;
|
||||
}
|
||||
|
||||
unsigned
|
||||
RingBuffer::size()
|
||||
{
|
||||
return (_buf != nullptr) ? _num_items : 0;
|
||||
}
|
||||
|
||||
void
|
||||
RingBuffer::flush()
|
||||
{
|
||||
while (!empty())
|
||||
get(NULL);
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(const void *val, size_t val_size)
|
||||
{
|
||||
unsigned next = _next(_head);
|
||||
if (next != _tail) {
|
||||
if ((val_size == 0) || (val_size > _item_size))
|
||||
val_size = _item_size;
|
||||
memcpy(&_buf[_head * _item_size], val, val_size);
|
||||
_head = next;
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(int8_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(uint8_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(int16_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(uint16_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(int32_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(uint32_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(int64_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(uint64_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(float val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(double val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(const void *val, size_t val_size)
|
||||
{
|
||||
bool overwrote = false;
|
||||
|
||||
for (;;) {
|
||||
if (put(val, val_size))
|
||||
break;
|
||||
get(NULL);
|
||||
overwrote = true;
|
||||
}
|
||||
return overwrote;
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(int8_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(uint8_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(int16_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(uint16_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(int32_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(uint32_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(int64_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(uint64_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(float val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(double val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
// FIXME - clang crashes on this get() call
|
||||
#ifdef __PX4_QURT
|
||||
#define __PX4_SBCAP my_sync_bool_compare_and_swap
|
||||
static inline bool my_sync_bool_compare_and_swap(volatile unsigned *a, unsigned b, unsigned c)
|
||||
{
|
||||
if (*a == b) {
|
||||
*a = c;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
#else
|
||||
#define __PX4_SBCAP __sync_bool_compare_and_swap
|
||||
#endif
|
||||
bool
|
||||
RingBuffer::get(void *val, size_t val_size)
|
||||
{
|
||||
if (_tail != _head) {
|
||||
unsigned candidate;
|
||||
unsigned next;
|
||||
|
||||
if ((val_size == 0) || (val_size > _item_size))
|
||||
val_size = _item_size;
|
||||
|
||||
do {
|
||||
/* decide which element we think we're going to read */
|
||||
candidate = _tail;
|
||||
|
||||
/* and what the corresponding next index will be */
|
||||
next = _next(candidate);
|
||||
|
||||
/* go ahead and read from this index */
|
||||
if (val != NULL)
|
||||
memcpy(val, &_buf[candidate * _item_size], val_size);
|
||||
|
||||
/* if the tail pointer didn't change, we got our item */
|
||||
} while (!__PX4_SBCAP(&_tail, candidate, next));
|
||||
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(int8_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(uint8_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(int16_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(uint16_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(int32_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(uint32_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(int64_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(uint64_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(float &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(double &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
unsigned
|
||||
RingBuffer::space(void)
|
||||
{
|
||||
unsigned tail, head;
|
||||
|
||||
/*
|
||||
* Make a copy of the head/tail pointers in a fashion that
|
||||
* may err on the side of under-estimating the free space
|
||||
* in the buffer in the case that the buffer is being updated
|
||||
* asynchronously with our check.
|
||||
* If the head pointer changes (reducing space) while copying,
|
||||
* re-try the copy.
|
||||
*/
|
||||
do {
|
||||
head = _head;
|
||||
tail = _tail;
|
||||
} while (head != _head);
|
||||
|
||||
return (tail >= head) ? (_num_items - (tail - head)) : (head - tail - 1);
|
||||
}
|
||||
|
||||
unsigned
|
||||
RingBuffer::count(void)
|
||||
{
|
||||
/*
|
||||
* Note that due to the conservative nature of space(), this may
|
||||
* over-estimate the number of items in the buffer.
|
||||
*/
|
||||
return _num_items - space();
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::resize(unsigned new_size)
|
||||
{
|
||||
char *old_buffer;
|
||||
char *new_buffer = new char [(new_size+1) * _item_size];
|
||||
if (new_buffer == nullptr) {
|
||||
return false;
|
||||
}
|
||||
old_buffer = _buf;
|
||||
_buf = new_buffer;
|
||||
_num_items = new_size;
|
||||
_head = new_size;
|
||||
_tail = new_size;
|
||||
delete[] old_buffer;
|
||||
return true;
|
||||
}
|
||||
|
||||
void
|
||||
RingBuffer::print_info(const char *name)
|
||||
{
|
||||
printf("%s %u/%lu (%u/%u @ %p)\n",
|
||||
name,
|
||||
_num_items,
|
||||
(unsigned long)_num_items * _item_size,
|
||||
_head,
|
||||
_tail,
|
||||
_buf);
|
||||
}
|
||||
+10
-343
@@ -39,6 +39,10 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stddef.h>
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
|
||||
class RingBuffer {
|
||||
public:
|
||||
RingBuffer(unsigned ring_size, size_t entry_size);
|
||||
@@ -168,346 +172,9 @@ private:
|
||||
RingBuffer operator=(const RingBuffer&);
|
||||
};
|
||||
|
||||
RingBuffer::RingBuffer(unsigned num_items, size_t item_size) :
|
||||
_num_items(num_items),
|
||||
_item_size(item_size),
|
||||
_buf(new char[(_num_items+1) * item_size]),
|
||||
_head(_num_items),
|
||||
_tail(_num_items)
|
||||
{}
|
||||
|
||||
RingBuffer::~RingBuffer()
|
||||
{
|
||||
if (_buf != nullptr)
|
||||
delete[] _buf;
|
||||
}
|
||||
|
||||
unsigned
|
||||
RingBuffer::_next(unsigned index)
|
||||
{
|
||||
return (0 == index) ? _num_items : (index - 1);
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::empty()
|
||||
{
|
||||
return _tail == _head;
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::full()
|
||||
{
|
||||
return _next(_head) == _tail;
|
||||
}
|
||||
|
||||
unsigned
|
||||
RingBuffer::size()
|
||||
{
|
||||
return (_buf != nullptr) ? _num_items : 0;
|
||||
}
|
||||
|
||||
void
|
||||
RingBuffer::flush()
|
||||
{
|
||||
while (!empty())
|
||||
get(NULL);
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(const void *val, size_t val_size)
|
||||
{
|
||||
unsigned next = _next(_head);
|
||||
if (next != _tail) {
|
||||
if ((val_size == 0) || (val_size > _item_size))
|
||||
val_size = _item_size;
|
||||
memcpy(&_buf[_head * _item_size], val, val_size);
|
||||
_head = next;
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(int8_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(uint8_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(int16_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(uint16_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(int32_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(uint32_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(int64_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(uint64_t val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(float val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::put(double val)
|
||||
{
|
||||
return put(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(const void *val, size_t val_size)
|
||||
{
|
||||
bool overwrote = false;
|
||||
|
||||
for (;;) {
|
||||
if (put(val, val_size))
|
||||
break;
|
||||
get(NULL);
|
||||
overwrote = true;
|
||||
}
|
||||
return overwrote;
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(int8_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(uint8_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(int16_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(uint16_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(int32_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(uint32_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(int64_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(uint64_t val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(float val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::force(double val)
|
||||
{
|
||||
return force(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(void *val, size_t val_size)
|
||||
{
|
||||
if (_tail != _head) {
|
||||
unsigned candidate;
|
||||
unsigned next;
|
||||
|
||||
if ((val_size == 0) || (val_size > _item_size))
|
||||
val_size = _item_size;
|
||||
|
||||
do {
|
||||
/* decide which element we think we're going to read */
|
||||
candidate = _tail;
|
||||
|
||||
/* and what the corresponding next index will be */
|
||||
next = _next(candidate);
|
||||
|
||||
/* go ahead and read from this index */
|
||||
if (val != NULL)
|
||||
memcpy(val, &_buf[candidate * _item_size], val_size);
|
||||
|
||||
/* if the tail pointer didn't change, we got our item */
|
||||
} while (!__sync_bool_compare_and_swap(&_tail, candidate, next));
|
||||
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(int8_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(uint8_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(int16_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(uint16_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(int32_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(uint32_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(int64_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(uint64_t &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(float &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::get(double &val)
|
||||
{
|
||||
return get(&val, sizeof(val));
|
||||
}
|
||||
|
||||
unsigned
|
||||
RingBuffer::space(void)
|
||||
{
|
||||
unsigned tail, head;
|
||||
|
||||
/*
|
||||
* Make a copy of the head/tail pointers in a fashion that
|
||||
* may err on the side of under-estimating the free space
|
||||
* in the buffer in the case that the buffer is being updated
|
||||
* asynchronously with our check.
|
||||
* If the head pointer changes (reducing space) while copying,
|
||||
* re-try the copy.
|
||||
*/
|
||||
do {
|
||||
head = _head;
|
||||
tail = _tail;
|
||||
} while (head != _head);
|
||||
|
||||
return (tail >= head) ? (_num_items - (tail - head)) : (head - tail - 1);
|
||||
}
|
||||
|
||||
unsigned
|
||||
RingBuffer::count(void)
|
||||
{
|
||||
/*
|
||||
* Note that due to the conservative nature of space(), this may
|
||||
* over-estimate the number of items in the buffer.
|
||||
*/
|
||||
return _num_items - space();
|
||||
}
|
||||
|
||||
bool
|
||||
RingBuffer::resize(unsigned new_size)
|
||||
{
|
||||
char *old_buffer;
|
||||
char *new_buffer = new char [(new_size+1) * _item_size];
|
||||
if (new_buffer == nullptr) {
|
||||
return false;
|
||||
}
|
||||
old_buffer = _buf;
|
||||
_buf = new_buffer;
|
||||
_num_items = new_size;
|
||||
_head = new_size;
|
||||
_tail = new_size;
|
||||
delete[] old_buffer;
|
||||
return true;
|
||||
}
|
||||
|
||||
void
|
||||
RingBuffer::print_info(const char *name)
|
||||
{
|
||||
printf("%s %u/%u (%u/%u @ %p)\n",
|
||||
name,
|
||||
_num_items,
|
||||
_num_items * _item_size,
|
||||
_head,
|
||||
_tail,
|
||||
_buf);
|
||||
}
|
||||
#ifdef __PX4_NUTTX
|
||||
// Not sure why NuttX requires these to be defined in the header file
|
||||
// but on other targets it causes a problem with multiple definitions
|
||||
// at link time
|
||||
#include "ringbuffer.cpp"
|
||||
#endif
|
||||
|
||||
@@ -0,0 +1,116 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2015 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 sim.cpp
|
||||
*
|
||||
* Base class for simulated devices.
|
||||
*
|
||||
* @todo Bus frequency changes; currently we do nothing with the value
|
||||
* that is supplied. Should we just depend on the bus knowing?
|
||||
*/
|
||||
|
||||
#include <px4_log.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include "sim.h"
|
||||
|
||||
namespace device
|
||||
{
|
||||
|
||||
SIM::SIM(const char *name,
|
||||
const char *devname,
|
||||
int bus,
|
||||
uint16_t address) :
|
||||
// base class
|
||||
Device(name),
|
||||
// public
|
||||
// protected
|
||||
// private
|
||||
_bus(bus),
|
||||
_address(address),
|
||||
_devname(devname)
|
||||
{
|
||||
|
||||
PX4_DEBUG("SIM::SIM name = %s devname = %s", name, devname);
|
||||
// fill in _device_id fields for a SIM device
|
||||
_device_id.devid_s.bus_type = DeviceBusType_SIM;
|
||||
_device_id.devid_s.bus = bus;
|
||||
_device_id.devid_s.address = address;
|
||||
// devtype needs to be filled in by the driver
|
||||
_device_id.devid_s.devtype = 0;
|
||||
}
|
||||
|
||||
SIM::~SIM()
|
||||
{
|
||||
}
|
||||
|
||||
int
|
||||
SIM::init()
|
||||
{
|
||||
int ret = PX4_OK;
|
||||
|
||||
// Assume the driver set the desired bus frequency. There is no standard
|
||||
// way to set it from user space.
|
||||
|
||||
// do base class init, which registers the virtual driver
|
||||
ret = Device::init();
|
||||
|
||||
if (ret != PX4_OK) {
|
||||
PX4_ERR("VDev::init failed");
|
||||
return ret;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
SIM::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len)
|
||||
{
|
||||
if (send_len > 0) {
|
||||
PX4_DEBUG("SIM: sending %d bytes", send_len);
|
||||
}
|
||||
|
||||
if (recv_len > 0) {
|
||||
PX4_DEBUG("SIM: receiving %d bytes", recv_len);
|
||||
|
||||
// TODO - write data to recv;
|
||||
}
|
||||
|
||||
PX4_DEBUG("I2C SIM: transfer_4 on %s", _devname);
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
} // namespace device
|
||||
@@ -0,0 +1,112 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 sim.h
|
||||
*
|
||||
* Base class for devices on simulation bus.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "vdev.h"
|
||||
|
||||
namespace device __EXPORT
|
||||
{
|
||||
|
||||
/**
|
||||
* Abstract class for character device on SIM
|
||||
*/
|
||||
class __EXPORT SIM : public Device
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
/**
|
||||
* Get the address
|
||||
*/
|
||||
int16_t get_address() const { return _address; }
|
||||
|
||||
protected:
|
||||
/**
|
||||
* The number of times a read or write operation will be retried on
|
||||
* error.
|
||||
*/
|
||||
unsigned _retries;
|
||||
|
||||
/**
|
||||
* The SIM bus number the device is attached to.
|
||||
*/
|
||||
int _bus;
|
||||
|
||||
/**
|
||||
* @ Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param devname Device node name
|
||||
* @param bus SIM bus on which the device lives
|
||||
* @param address SIM bus address, or zero if set_address will be used
|
||||
*/
|
||||
SIM(const char *name,
|
||||
const char *devname,
|
||||
int bus,
|
||||
uint16_t address);
|
||||
virtual ~SIM();
|
||||
|
||||
virtual int init();
|
||||
|
||||
/**
|
||||
* Perform an SIM transaction to the device.
|
||||
*
|
||||
* At least one of send_len and recv_len must be non-zero.
|
||||
*
|
||||
* @param send Pointer to bytes to send.
|
||||
* @param send_len Number of bytes to send.
|
||||
* @param recv Pointer to buffer for bytes received.
|
||||
* @param recv_len Number of bytes to receive.
|
||||
* @return OK if the transfer was successful, -errno
|
||||
* otherwise.
|
||||
*/
|
||||
virtual int transfer(const uint8_t *send, unsigned send_len,
|
||||
uint8_t *recv, unsigned recv_len);
|
||||
|
||||
private:
|
||||
uint16_t _address;
|
||||
const char * _devname;
|
||||
|
||||
SIM(const device::SIM&);
|
||||
SIM operator=(const device::SIM&);
|
||||
};
|
||||
|
||||
} // namespace device
|
||||
|
||||
@@ -42,7 +42,7 @@
|
||||
|
||||
#include "device.h"
|
||||
|
||||
#include <nuttx/spi.h>
|
||||
#include <px4_spi.h>
|
||||
|
||||
namespace device __EXPORT
|
||||
{
|
||||
@@ -50,7 +50,11 @@ namespace device __EXPORT
|
||||
/**
|
||||
* Abstract class for character device on SPI
|
||||
*/
|
||||
#ifdef __PX4_NUTTX
|
||||
class __EXPORT SPI : public CDev
|
||||
#else
|
||||
class __EXPORT SPI : public VDev
|
||||
#endif
|
||||
{
|
||||
protected:
|
||||
/**
|
||||
|
||||
@@ -0,0 +1,524 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file vcdev.cpp
|
||||
*
|
||||
* Virtual character device base class.
|
||||
*/
|
||||
|
||||
#include "px4_posix.h"
|
||||
#include "vdev.h"
|
||||
#include "drivers/drv_device.h"
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
|
||||
namespace device
|
||||
{
|
||||
|
||||
int px4_errno;
|
||||
|
||||
struct px4_dev_t {
|
||||
char *name;
|
||||
void *cdev;
|
||||
|
||||
px4_dev_t(const char *n, void *c) : cdev(c) {
|
||||
name = strdup(n);
|
||||
}
|
||||
|
||||
~px4_dev_t() { free(name); }
|
||||
|
||||
private:
|
||||
px4_dev_t() {}
|
||||
};
|
||||
|
||||
#define PX4_MAX_DEV 30
|
||||
static px4_dev_t *devmap[PX4_MAX_DEV];
|
||||
|
||||
/*
|
||||
* The standard NuttX operation dispatch table can't call C++ member functions
|
||||
* directly, so we have to bounce them through this dispatch table.
|
||||
*/
|
||||
|
||||
VDev::VDev(const char *name,
|
||||
const char *devname) :
|
||||
// base class
|
||||
Device(name),
|
||||
// public
|
||||
// protected
|
||||
_pub_blocked(false),
|
||||
// private
|
||||
_devname(devname),
|
||||
_registered(false),
|
||||
_open_count(0)
|
||||
{
|
||||
PX4_DEBUG("VDev::VDev");
|
||||
for (unsigned i = 0; i < _max_pollwaiters; i++)
|
||||
_pollset[i] = nullptr;
|
||||
}
|
||||
|
||||
VDev::~VDev()
|
||||
{
|
||||
PX4_DEBUG("VDev::~VDev");
|
||||
if (_registered)
|
||||
unregister_driver(_devname);
|
||||
}
|
||||
|
||||
int
|
||||
VDev::register_class_devname(const char *class_devname)
|
||||
{
|
||||
PX4_DEBUG("VDev::register_class_devname");
|
||||
if (class_devname == nullptr) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
int class_instance = 0;
|
||||
int ret = -ENOSPC;
|
||||
|
||||
while (class_instance < 4) {
|
||||
char name[32];
|
||||
snprintf(name, sizeof(name), "%s%d", class_devname, class_instance);
|
||||
ret = register_driver(name, (void *)this);
|
||||
if (ret == OK) break;
|
||||
class_instance++;
|
||||
}
|
||||
|
||||
if (class_instance == 4) {
|
||||
return ret;
|
||||
}
|
||||
return class_instance;
|
||||
}
|
||||
|
||||
int
|
||||
VDev::register_driver(const char *name, void *data)
|
||||
{
|
||||
PX4_DEBUG("VDev::register_driver");
|
||||
int ret = -ENOSPC;
|
||||
|
||||
if (name == NULL || data == NULL)
|
||||
return -EINVAL;
|
||||
|
||||
// Make sure the device does not already exist
|
||||
// FIXME - convert this to a map for efficiency
|
||||
for (int i=0;i<PX4_MAX_DEV; ++i) {
|
||||
if (devmap[i] && (strcmp(devmap[i]->name,name) == 0)) {
|
||||
return -EEXIST;
|
||||
}
|
||||
}
|
||||
for (int i=0;i<PX4_MAX_DEV; ++i) {
|
||||
if (devmap[i] == NULL) {
|
||||
devmap[i] = new px4_dev_t(name, (void *)data);
|
||||
PX4_DEBUG("Registered DEV %s", name);
|
||||
ret = PX4_OK;
|
||||
break;
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
VDev::unregister_driver(const char *name)
|
||||
{
|
||||
PX4_DEBUG("VDev::unregister_driver");
|
||||
int ret = -ENOSPC;
|
||||
|
||||
if (name == NULL)
|
||||
return -EINVAL;
|
||||
|
||||
for (int i=0;i<PX4_MAX_DEV; ++i) {
|
||||
if (devmap[i] && (strcmp(name, devmap[i]->name) == 0)) {
|
||||
delete devmap[i];
|
||||
devmap[i] = NULL;
|
||||
PX4_DEBUG("Unregistered DEV %s", name);
|
||||
ret = PX4_OK;
|
||||
break;
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
VDev::unregister_class_devname(const char *class_devname, unsigned class_instance)
|
||||
{
|
||||
PX4_DEBUG("VDev::unregister_class_devname");
|
||||
char name[32];
|
||||
snprintf(name, sizeof(name), "%s%u", class_devname, class_instance);
|
||||
for (int i=0;i<PX4_MAX_DEV; ++i) {
|
||||
if (devmap[i] && strcmp(devmap[i]->name,name) == 0) {
|
||||
delete devmap[i];
|
||||
PX4_DEBUG("Unregistered class DEV %s", name);
|
||||
devmap[i] = NULL;
|
||||
return PX4_OK;
|
||||
}
|
||||
}
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
int
|
||||
VDev::init()
|
||||
{
|
||||
PX4_DEBUG("VDev::init");
|
||||
|
||||
// base class init first
|
||||
int ret = Device::init();
|
||||
|
||||
if (ret != PX4_OK)
|
||||
goto out;
|
||||
|
||||
// now register the driver
|
||||
if (_devname != nullptr) {
|
||||
ret = register_driver(_devname, (void *)this);
|
||||
|
||||
if (ret != PX4_OK)
|
||||
goto out;
|
||||
|
||||
_registered = true;
|
||||
}
|
||||
|
||||
out:
|
||||
return ret;
|
||||
}
|
||||
|
||||
/*
|
||||
* Default implementations of the character device interface
|
||||
*/
|
||||
int
|
||||
VDev::open(file_t *filep)
|
||||
{
|
||||
PX4_DEBUG("VDev::open");
|
||||
int ret = PX4_OK;
|
||||
|
||||
lock();
|
||||
/* increment the open count */
|
||||
_open_count++;
|
||||
|
||||
if (_open_count == 1) {
|
||||
|
||||
/* first-open callback may decline the open */
|
||||
ret = open_first(filep);
|
||||
|
||||
if (ret != PX4_OK)
|
||||
_open_count--;
|
||||
}
|
||||
|
||||
unlock();
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
VDev::open_first(file_t *filep)
|
||||
{
|
||||
PX4_DEBUG("VDev::open_first");
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
int
|
||||
VDev::close(file_t *filep)
|
||||
{
|
||||
PX4_DEBUG("VDev::close");
|
||||
int ret = PX4_OK;
|
||||
|
||||
lock();
|
||||
|
||||
if (_open_count > 0) {
|
||||
/* decrement the open count */
|
||||
_open_count--;
|
||||
|
||||
/* callback cannot decline the close */
|
||||
if (_open_count == 0)
|
||||
ret = close_last(filep);
|
||||
|
||||
} else {
|
||||
ret = -EBADF;
|
||||
}
|
||||
|
||||
unlock();
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
VDev::close_last(file_t *filep)
|
||||
{
|
||||
PX4_DEBUG("VDev::close_last");
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
ssize_t
|
||||
VDev::read(file_t *filep, char *buffer, size_t buflen)
|
||||
{
|
||||
PX4_DEBUG("VDev::read");
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
ssize_t
|
||||
VDev::write(file_t *filep, const char *buffer, size_t buflen)
|
||||
{
|
||||
PX4_DEBUG("VDev::write");
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
off_t
|
||||
VDev::seek(file_t *filep, off_t offset, int whence)
|
||||
{
|
||||
PX4_DEBUG("VDev::seek");
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
int
|
||||
VDev::ioctl(file_t *filep, int cmd, unsigned long arg)
|
||||
{
|
||||
PX4_DEBUG("VDev::ioctl");
|
||||
int ret = -ENOTTY;
|
||||
|
||||
switch (cmd) {
|
||||
|
||||
/* fetch a pointer to the driver's private data */
|
||||
case DIOC_GETPRIV:
|
||||
*(void **)(uintptr_t)arg = (void *)this;
|
||||
ret = PX4_OK;
|
||||
break;
|
||||
case DEVIOCSPUBBLOCK:
|
||||
_pub_blocked = (arg != 0);
|
||||
ret = PX4_OK;
|
||||
break;
|
||||
case DEVIOCGPUBBLOCK:
|
||||
ret = _pub_blocked;
|
||||
break;
|
||||
case DEVIOCGDEVICEID:
|
||||
ret = (int)_device_id.devid;
|
||||
PX4_INFO("IOCTL DEVIOCGDEVICEID %d", ret);
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
VDev::poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup)
|
||||
{
|
||||
PX4_DEBUG("VDev::Poll %s", setup ? "setup" : "teardown");
|
||||
int ret = PX4_OK;
|
||||
|
||||
/*
|
||||
* Lock against pollnotify() (and possibly other callers)
|
||||
*/
|
||||
lock();
|
||||
|
||||
if (setup) {
|
||||
/*
|
||||
* Save the file pointer in the pollfd for the subclass'
|
||||
* benefit.
|
||||
*/
|
||||
fds->priv = (void *)filep;
|
||||
PX4_DEBUG("VDev::poll: fds->priv = %p", filep);
|
||||
|
||||
/*
|
||||
* Handle setup requests.
|
||||
*/
|
||||
ret = store_poll_waiter(fds);
|
||||
|
||||
if (ret == PX4_OK) {
|
||||
|
||||
/*
|
||||
* Check to see whether we should send a poll notification
|
||||
* immediately.
|
||||
*/
|
||||
fds->revents |= fds->events & poll_state(filep);
|
||||
|
||||
/* yes? post the notification */
|
||||
if (fds->revents != 0)
|
||||
sem_post(fds->sem);
|
||||
}
|
||||
|
||||
} else {
|
||||
/*
|
||||
* Handle a teardown request.
|
||||
*/
|
||||
ret = remove_poll_waiter(fds);
|
||||
}
|
||||
|
||||
unlock();
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
VDev::poll_notify(pollevent_t events)
|
||||
{
|
||||
PX4_DEBUG("VDev::poll_notify events = %0x", events);
|
||||
|
||||
/* lock against poll() as well as other wakeups */
|
||||
lock();
|
||||
|
||||
for (unsigned i = 0; i < _max_pollwaiters; i++)
|
||||
if (nullptr != _pollset[i])
|
||||
poll_notify_one(_pollset[i], events);
|
||||
|
||||
unlock();
|
||||
}
|
||||
|
||||
void
|
||||
VDev::poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events)
|
||||
{
|
||||
PX4_DEBUG("VDev::poll_notify_one");
|
||||
int value;
|
||||
sem_getvalue(fds->sem, &value);
|
||||
|
||||
/* update the reported event set */
|
||||
fds->revents |= fds->events & events;
|
||||
|
||||
PX4_DEBUG(" Events fds=%p %0x %0x %0x %d",fds, fds->revents, fds->events, events, value);
|
||||
|
||||
/* if the state is now interesting, wake the waiter if it's still asleep */
|
||||
/* XXX semcount check here is a vile hack; counting semphores should not be abused as cvars */
|
||||
if ((fds->revents != 0) && (value <= 0))
|
||||
sem_post(fds->sem);
|
||||
}
|
||||
|
||||
pollevent_t
|
||||
VDev::poll_state(file_t *filep)
|
||||
{
|
||||
PX4_DEBUG("VDev::poll_notify");
|
||||
/* by default, no poll events to report */
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
VDev::store_poll_waiter(px4_pollfd_struct_t *fds)
|
||||
{
|
||||
/*
|
||||
* Look for a free slot.
|
||||
*/
|
||||
PX4_DEBUG("VDev::store_poll_waiter");
|
||||
for (unsigned i = 0; i < _max_pollwaiters; i++) {
|
||||
if (nullptr == _pollset[i]) {
|
||||
|
||||
/* save the pollfd */
|
||||
_pollset[i] = fds;
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
}
|
||||
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
int
|
||||
VDev::remove_poll_waiter(px4_pollfd_struct_t *fds)
|
||||
{
|
||||
PX4_DEBUG("VDev::remove_poll_waiter");
|
||||
for (unsigned i = 0; i < _max_pollwaiters; i++) {
|
||||
if (fds == _pollset[i]) {
|
||||
|
||||
_pollset[i] = nullptr;
|
||||
return PX4_OK;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
PX4_WARN("poll: bad fd state");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
VDev *VDev::getDev(const char *path)
|
||||
{
|
||||
PX4_DEBUG("VDev::getDev");
|
||||
int i=0;
|
||||
for (; i<PX4_MAX_DEV; ++i) {
|
||||
//if (devmap[i]) {
|
||||
// printf("%s %s\n", devmap[i]->name, path);
|
||||
//}
|
||||
if (devmap[i] && (strcmp(devmap[i]->name, path) == 0)) {
|
||||
return (VDev *)(devmap[i]->cdev);
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void VDev::showDevices()
|
||||
{
|
||||
int i=0;
|
||||
PX4_INFO("Devices:\n");
|
||||
for (; i<PX4_MAX_DEV; ++i) {
|
||||
if (devmap[i] && strncmp(devmap[i]->name, "/dev/", 5) == 0) {
|
||||
PX4_INFO(" %s\n", devmap[i]->name);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void VDev::showTopics()
|
||||
{
|
||||
int i=0;
|
||||
PX4_INFO("Devices:\n");
|
||||
for (; i<PX4_MAX_DEV; ++i) {
|
||||
if (devmap[i] && strncmp(devmap[i]->name, "/obj/", 5) == 0) {
|
||||
PX4_INFO(" %s\n", devmap[i]->name);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void VDev::showFiles()
|
||||
{
|
||||
int i=0;
|
||||
PX4_INFO("Files:\n");
|
||||
for (; i<PX4_MAX_DEV; ++i) {
|
||||
if (devmap[i] && strncmp(devmap[i]->name, "/obj/", 5) != 0 &&
|
||||
strncmp(devmap[i]->name, "/dev/", 5) != 0) {
|
||||
PX4_INFO(" %s\n", devmap[i]->name);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
const char *VDev::topicList(unsigned int *next)
|
||||
{
|
||||
for (;*next<PX4_MAX_DEV; (*next)++)
|
||||
if (devmap[*next] && strncmp(devmap[(*next)]->name, "/obj/", 5) == 0)
|
||||
return devmap[(*next)++]->name;
|
||||
return NULL;
|
||||
}
|
||||
|
||||
const char *VDev::devList(unsigned int *next)
|
||||
{
|
||||
for (;*next<PX4_MAX_DEV; (*next)++)
|
||||
if (devmap[*next] && strncmp(devmap[(*next)]->name, "/dev/", 5) == 0)
|
||||
return devmap[(*next)++]->name;
|
||||
return NULL;
|
||||
}
|
||||
|
||||
} // namespace device
|
||||
|
||||
@@ -0,0 +1,535 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file vdevice.h
|
||||
*
|
||||
* Definitions for the generic base classes in the virtual device framework.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
* Includes here should only cover the needs of the framework definitions.
|
||||
*/
|
||||
#include <px4_posix.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <stddef.h>
|
||||
#include <stdint.h>
|
||||
#include <semaphore.h>
|
||||
|
||||
/**
|
||||
* Namespace encapsulating all device framework classes, functions and data.
|
||||
*/
|
||||
namespace device __EXPORT
|
||||
{
|
||||
|
||||
struct file_t {
|
||||
int fd;
|
||||
int flags;
|
||||
mode_t mode;
|
||||
void *priv;
|
||||
void *vdev;
|
||||
|
||||
file_t() : fd(-1), flags(0), priv(NULL), vdev(NULL) {}
|
||||
file_t(int f, void *c, int d) : fd(d), flags(f), priv(NULL), vdev(c) {}
|
||||
};
|
||||
|
||||
/**
|
||||
* Fundamental base class for all physical drivers (I2C, SPI).
|
||||
*
|
||||
* This class provides the basic driver template for I2C and SPI devices
|
||||
*/
|
||||
class __EXPORT Device
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Destructor.
|
||||
*
|
||||
* Public so that anonymous devices can be destroyed.
|
||||
*/
|
||||
virtual ~Device();
|
||||
|
||||
/*
|
||||
* Direct access methods.
|
||||
*/
|
||||
|
||||
/**
|
||||
* Initialise the driver and make it ready for use.
|
||||
*
|
||||
* @return OK if the driver initialized OK, negative errno otherwise;
|
||||
*/
|
||||
virtual int init();
|
||||
|
||||
/**
|
||||
* Read directly from the device.
|
||||
*
|
||||
* The actual size of each unit quantity is device-specific.
|
||||
*
|
||||
* @param offset The device address at which to start reading
|
||||
* @param data The buffer into which the read values should be placed.
|
||||
* @param count The number of items to read.
|
||||
* @return The number of items read on success, negative errno otherwise.
|
||||
*/
|
||||
virtual int dev_read(unsigned address, void *data, unsigned count);
|
||||
|
||||
/**
|
||||
* Write directly to the device.
|
||||
*
|
||||
* The actual size of each unit quantity is device-specific.
|
||||
*
|
||||
* @param address The device address at which to start writing.
|
||||
* @param data The buffer from which values should be read.
|
||||
* @param count The number of items to write.
|
||||
* @return The number of items written on success, negative errno otherwise.
|
||||
*/
|
||||
virtual int dev_write(unsigned address, void *data, unsigned count);
|
||||
|
||||
/**
|
||||
* Perform a device-specific operation.
|
||||
*
|
||||
* @param operation The operation to perform.
|
||||
* @param arg An argument to the operation.
|
||||
* @return Negative errno on error, OK or positive value on success.
|
||||
*/
|
||||
virtual int dev_ioctl(unsigned operation, unsigned &arg);
|
||||
|
||||
/*
|
||||
device bus types for DEVID
|
||||
*/
|
||||
enum DeviceBusType {
|
||||
DeviceBusType_UNKNOWN = 0,
|
||||
DeviceBusType_I2C = 1,
|
||||
DeviceBusType_SPI = 2,
|
||||
DeviceBusType_UAVCAN = 3,
|
||||
DeviceBusType_SIM = 4,
|
||||
};
|
||||
|
||||
/*
|
||||
broken out device elements. The bitfields are used to keep
|
||||
the overall value small enough to fit in a float accurately,
|
||||
which makes it possible to transport over the MAVLink
|
||||
parameter protocol without loss of information.
|
||||
*/
|
||||
struct DeviceStructure {
|
||||
enum DeviceBusType bus_type:3;
|
||||
uint8_t bus:5; // which instance of the bus type
|
||||
uint8_t address; // address on the bus (eg. I2C address)
|
||||
uint8_t devtype; // device class specific device type
|
||||
};
|
||||
|
||||
union DeviceId {
|
||||
struct DeviceStructure devid_s;
|
||||
uint32_t devid;
|
||||
};
|
||||
|
||||
protected:
|
||||
const char *_name; /**< driver name */
|
||||
bool _debug_enabled; /**< if true, debug messages are printed */
|
||||
union DeviceId _device_id; /**< device identifier information */
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
*/
|
||||
Device(const char *name);
|
||||
|
||||
/**
|
||||
* Take the driver lock.
|
||||
*
|
||||
* Each driver instance has its own lock/semaphore.
|
||||
*
|
||||
* Note that we must loop as the wait may be interrupted by a signal.
|
||||
*/
|
||||
void lock() {
|
||||
debug("lock");
|
||||
do {} while (sem_wait(&_lock) != 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Release the driver lock.
|
||||
*/
|
||||
void unlock() {
|
||||
debug("unlock");
|
||||
sem_post(&_lock);
|
||||
}
|
||||
|
||||
/**
|
||||
* Log a message.
|
||||
*
|
||||
* The message is prefixed with the driver name, and followed
|
||||
* by a newline.
|
||||
*/
|
||||
void log(const char *fmt, ...);
|
||||
|
||||
/**
|
||||
* Print a debug message.
|
||||
*
|
||||
* The message is prefixed with the driver name, and followed
|
||||
* by a newline.
|
||||
*/
|
||||
void debug(const char *fmt, ...);
|
||||
|
||||
private:
|
||||
sem_t _lock;
|
||||
|
||||
/** disable copy construction for this and all subclasses */
|
||||
Device(const Device &);
|
||||
|
||||
/** disable assignment for this and all subclasses */
|
||||
Device &operator = (const Device &);
|
||||
};
|
||||
|
||||
/**
|
||||
* Abstract class for any virtual character device
|
||||
*/
|
||||
class __EXPORT VDev : public Device
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param devname Device node name
|
||||
*/
|
||||
VDev(const char *name, const char *devname);
|
||||
|
||||
/**
|
||||
* Destructor
|
||||
*/
|
||||
virtual ~VDev();
|
||||
|
||||
virtual int init();
|
||||
|
||||
/**
|
||||
* Perform a poll setup/teardown operation. Based on NuttX implementation.
|
||||
*
|
||||
* This is handled internally and should not normally be overridden.
|
||||
*
|
||||
* @param filep Pointer to the internal file structure.
|
||||
* @param fds Poll descriptor being waited on.
|
||||
* @param setup True if this is establishing a request, false if
|
||||
* it is being torn down.
|
||||
* @return OK on success, or -errno otherwise.
|
||||
*/
|
||||
virtual int poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup);
|
||||
|
||||
/**
|
||||
* Test whether the device is currently open.
|
||||
*
|
||||
* This can be used to avoid tearing down a device that is still active.
|
||||
* Note - not virtual, cannot be overridden by a subclass.
|
||||
*
|
||||
* @return True if the device is currently open.
|
||||
*/
|
||||
bool is_open() { return _open_count > 0; }
|
||||
|
||||
/**
|
||||
* Handle an open of the device.
|
||||
*
|
||||
* This function is called for every open of the device. The default
|
||||
* implementation maintains _open_count and always returns OK.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @return OK if the open is allowed, -errno otherwise.
|
||||
*/
|
||||
virtual int open(file_t *filep);
|
||||
|
||||
/**
|
||||
* Handle a close of the device.
|
||||
*
|
||||
* This function is called for every close of the device. The default
|
||||
* implementation maintains _open_count and returns OK as long as it is not zero.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @return OK if the close was successful, -errno otherwise.
|
||||
*/
|
||||
virtual int close(file_t *filep);
|
||||
|
||||
/**
|
||||
* Perform a read from the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @param buffer Pointer to the buffer into which data should be placed.
|
||||
* @param buflen The number of bytes to be read.
|
||||
* @return The number of bytes read or -errno otherwise.
|
||||
*/
|
||||
virtual ssize_t read(file_t *filep, char *buffer, size_t buflen);
|
||||
|
||||
/**
|
||||
* Perform a write to the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @param buffer Pointer to the buffer from which data should be read.
|
||||
* @param buflen The number of bytes to be written.
|
||||
* @return The number of bytes written or -errno otherwise.
|
||||
*/
|
||||
virtual ssize_t write(file_t *filep, const char *buffer, size_t buflen);
|
||||
|
||||
/**
|
||||
* Perform a logical seek operation on the device.
|
||||
*
|
||||
* The default implementation returns -ENOSYS.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @param offset The new file position relative to whence.
|
||||
* @param whence SEEK_OFS, SEEK_CUR or SEEK_END.
|
||||
* @return The previous offset, or -errno otherwise.
|
||||
*/
|
||||
virtual off_t seek(file_t *filep, off_t offset, int whence);
|
||||
|
||||
/**
|
||||
* Perform an ioctl operation on the device.
|
||||
*
|
||||
* The default implementation handles DIOC_GETPRIV, and otherwise
|
||||
* returns -ENOTTY. Subclasses should call the default implementation
|
||||
* for any command they do not handle themselves.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @param cmd The ioctl command value.
|
||||
* @param arg The ioctl argument value.
|
||||
* @return OK on success, or -errno otherwise.
|
||||
*/
|
||||
virtual int ioctl(file_t *filep, int cmd, unsigned long arg);
|
||||
|
||||
static VDev *getDev(const char *path);
|
||||
static void showFiles(void);
|
||||
static void showDevices(void);
|
||||
static void showTopics(void);
|
||||
static const char *devList(unsigned int *next);
|
||||
static const char *topicList(unsigned int *next);
|
||||
|
||||
protected:
|
||||
|
||||
int register_driver(const char *name, void *data);
|
||||
int unregister_driver(const char *name);
|
||||
|
||||
/**
|
||||
* Check the current state of the device for poll events from the
|
||||
* perspective of the file.
|
||||
*
|
||||
* This function is called by the default poll() implementation when
|
||||
* a poll is set up to determine whether the poll should return immediately.
|
||||
*
|
||||
* The default implementation returns no events.
|
||||
*
|
||||
* @param filep The file that's interested.
|
||||
* @return The current set of poll events.
|
||||
*/
|
||||
virtual pollevent_t poll_state(file_t *filep);
|
||||
|
||||
/**
|
||||
* Report new poll events.
|
||||
*
|
||||
* This function should be called anytime the state of the device changes
|
||||
* in a fashion that might be interesting to a poll waiter.
|
||||
*
|
||||
* @param events The new event(s) being announced.
|
||||
*/
|
||||
virtual void poll_notify(pollevent_t events);
|
||||
|
||||
/**
|
||||
* Internal implementation of poll_notify.
|
||||
*
|
||||
* @param fds A poll waiter to notify.
|
||||
* @param events The event(s) to send to the waiter.
|
||||
*/
|
||||
virtual void poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events);
|
||||
|
||||
/**
|
||||
* Notification of the first open.
|
||||
*
|
||||
* This function is called when the device open count transitions from zero
|
||||
* to one. The driver lock is held for the duration of the call.
|
||||
*
|
||||
* The default implementation returns OK.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @return OK if the open should proceed, -errno otherwise.
|
||||
*/
|
||||
virtual int open_first(file_t *filep);
|
||||
|
||||
/**
|
||||
* Notification of the last close.
|
||||
*
|
||||
* This function is called when the device open count transitions from
|
||||
* one to zero. The driver lock is held for the duration of the call.
|
||||
*
|
||||
* The default implementation returns OK.
|
||||
*
|
||||
* @param filep Pointer to the NuttX file structure.
|
||||
* @return OK if the open should return OK, -errno otherwise.
|
||||
*/
|
||||
virtual int close_last(file_t *filep);
|
||||
|
||||
/**
|
||||
* Register a class device name, automatically adding device
|
||||
* class instance suffix if need be.
|
||||
*
|
||||
* @param class_devname Device class name
|
||||
* @return class_instamce Class instance created, or -errno on failure
|
||||
*/
|
||||
virtual int register_class_devname(const char *class_devname);
|
||||
|
||||
/**
|
||||
* Register a class device name, automatically adding device
|
||||
* class instance suffix if need be.
|
||||
*
|
||||
* @param class_devname Device class name
|
||||
* @param class_instance Device class instance from register_class_devname()
|
||||
* @return OK on success, -errno otherwise
|
||||
*/
|
||||
virtual int unregister_class_devname(const char *class_devname, unsigned class_instance);
|
||||
|
||||
/**
|
||||
* Get the device name.
|
||||
*
|
||||
* @return the file system string of the device handle
|
||||
*/
|
||||
const char* get_devname() { return _devname; }
|
||||
|
||||
bool _pub_blocked; /**< true if publishing should be blocked */
|
||||
|
||||
private:
|
||||
static const unsigned _max_pollwaiters = 8;
|
||||
|
||||
const char *_devname; /**< device node name */
|
||||
bool _registered; /**< true if device name was registered */
|
||||
unsigned _open_count; /**< number of successful opens */
|
||||
|
||||
px4_pollfd_struct_t *_pollset[_max_pollwaiters];
|
||||
|
||||
/**
|
||||
* Store a pollwaiter in a slot where we can find it later.
|
||||
*
|
||||
* Expands the pollset as required. Must be called with the driver locked.
|
||||
*
|
||||
* @return OK, or -errno on error.
|
||||
*/
|
||||
int store_poll_waiter(px4_pollfd_struct_t *fds);
|
||||
|
||||
/**
|
||||
* Remove a poll waiter.
|
||||
*
|
||||
* @return OK, or -errno on error.
|
||||
*/
|
||||
int remove_poll_waiter(px4_pollfd_struct_t *fds);
|
||||
|
||||
/* do not allow copying this class */
|
||||
VDev(const VDev&);
|
||||
//VDev operator=(const VDev&);
|
||||
};
|
||||
|
||||
#if 0
|
||||
/**
|
||||
* Abstract class for character device accessed via PIO
|
||||
*/
|
||||
class __EXPORT VPIO : public CDev
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
*
|
||||
* @param name Driver name
|
||||
* @param devname Device node name
|
||||
* @param base Base address of the device PIO area
|
||||
* @param irq Interrupt assigned to the device (or zero if none)
|
||||
*/
|
||||
PIO(const char *name,
|
||||
const char *devname,
|
||||
unsigned long base
|
||||
);
|
||||
virtual ~PIO();
|
||||
|
||||
virtual int init();
|
||||
|
||||
protected:
|
||||
|
||||
/**
|
||||
* Read a register
|
||||
*
|
||||
* @param offset Register offset in bytes from the base address.
|
||||
*/
|
||||
uint32_t reg(uint32_t offset) {
|
||||
return *(volatile uint32_t *)(_base + offset);
|
||||
}
|
||||
|
||||
/**
|
||||
* Write a register
|
||||
*
|
||||
* @param offset Register offset in bytes from the base address.
|
||||
* @param value Value to write.
|
||||
*/
|
||||
void reg(uint32_t offset, uint32_t value) {
|
||||
*(volatile uint32_t *)(_base + offset) = value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Modify a register
|
||||
*
|
||||
* Note that there is a risk of a race during the read/modify/write cycle
|
||||
* that must be taken care of by the caller.
|
||||
*
|
||||
* @param offset Register offset in bytes from the base address.
|
||||
* @param clearbits Bits to clear in the register
|
||||
* @param setbits Bits to set in the register
|
||||
*/
|
||||
void modify(uint32_t offset, uint32_t clearbits, uint32_t setbits) {
|
||||
uint32_t val = reg(offset);
|
||||
val &= ~clearbits;
|
||||
val |= setbits;
|
||||
reg(offset, val);
|
||||
}
|
||||
|
||||
private:
|
||||
unsigned long _base;
|
||||
};
|
||||
#endif
|
||||
|
||||
} // namespace device
|
||||
|
||||
// class instance for primary driver of each class
|
||||
enum CLASS_DEVICE {
|
||||
CLASS_DEVICE_PRIMARY=0,
|
||||
CLASS_DEVICE_SECONDARY=1,
|
||||
CLASS_DEVICE_TERTIARY=2
|
||||
};
|
||||
|
||||
@@ -0,0 +1,322 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2015 Mark Charlebois. 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 vdev_posix.cpp
|
||||
*
|
||||
* POSIX-like API for virtual character device
|
||||
*/
|
||||
|
||||
#include <px4_log.h>
|
||||
#include <px4_posix.h>
|
||||
#include <px4_time.h>
|
||||
#include "device.h"
|
||||
#include "vfile.h"
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <pthread.h>
|
||||
#include <unistd.h>
|
||||
|
||||
using namespace device;
|
||||
|
||||
extern "C" {
|
||||
|
||||
struct timerData {
|
||||
sem_t &sem;
|
||||
struct timespec &ts;
|
||||
|
||||
timerData(sem_t &s, struct timespec &t) : sem(s), ts(t) {}
|
||||
~timerData() {}
|
||||
};
|
||||
|
||||
static void *timer_handler(void *data)
|
||||
{
|
||||
struct timerData *td = (struct timerData *)data;
|
||||
|
||||
if (td->ts.tv_sec) {
|
||||
sleep(td->ts.tv_sec);
|
||||
}
|
||||
usleep(td->ts.tv_nsec/1000);
|
||||
sem_post(&(td->sem));
|
||||
|
||||
PX4_DEBUG("timer_handler: Timer expired");
|
||||
return 0;
|
||||
}
|
||||
|
||||
#define PX4_MAX_FD 100
|
||||
static device::file_t *filemap[PX4_MAX_FD] = {};
|
||||
|
||||
int px4_errno;
|
||||
|
||||
inline bool valid_fd(int fd)
|
||||
{
|
||||
return (fd < PX4_MAX_FD && fd >= 0 && filemap[fd] != NULL);
|
||||
}
|
||||
|
||||
int px4_open(const char *path, int flags, ...)
|
||||
{
|
||||
PX4_DEBUG("px4_open");
|
||||
VDev *dev = VDev::getDev(path);
|
||||
int ret = 0;
|
||||
int i;
|
||||
mode_t mode;
|
||||
|
||||
if (!dev && (flags & (PX4_F_WRONLY|PX4_F_CREAT)) != 0 &&
|
||||
strncmp(path, "/obj/", 5) != 0 &&
|
||||
strncmp(path, "/dev/", 5) != 0)
|
||||
{
|
||||
va_list p;
|
||||
va_start(p, flags);
|
||||
mode = va_arg(p, mode_t);
|
||||
va_end(p);
|
||||
|
||||
// Create the file
|
||||
PX4_DEBUG("Creating virtual file %s", path);
|
||||
dev = VFile::createFile(path, mode);
|
||||
}
|
||||
if (dev) {
|
||||
for (i=0; i<PX4_MAX_FD; ++i) {
|
||||
if (filemap[i] == 0) {
|
||||
filemap[i] = new device::file_t(flags,dev,i);
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (i < PX4_MAX_FD) {
|
||||
ret = dev->open(filemap[i]);
|
||||
}
|
||||
else {
|
||||
ret = -ENOENT;
|
||||
}
|
||||
}
|
||||
else {
|
||||
ret = -EINVAL;
|
||||
}
|
||||
if (ret < 0) {
|
||||
px4_errno = -ret;
|
||||
return -1;
|
||||
}
|
||||
PX4_DEBUG("px4_open fd = %d", filemap[i]->fd);
|
||||
return filemap[i]->fd;
|
||||
}
|
||||
|
||||
int px4_close(int fd)
|
||||
{
|
||||
int ret;
|
||||
if (valid_fd(fd)) {
|
||||
VDev *dev = (VDev *)(filemap[fd]->vdev);
|
||||
PX4_DEBUG("px4_close fd = %d", fd);
|
||||
ret = dev->close(filemap[fd]);
|
||||
filemap[fd] = NULL;
|
||||
}
|
||||
else {
|
||||
ret = -EINVAL;
|
||||
}
|
||||
if (ret < 0) {
|
||||
px4_errno = -ret;
|
||||
ret = PX4_ERROR;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
ssize_t px4_read(int fd, void *buffer, size_t buflen)
|
||||
{
|
||||
int ret;
|
||||
if (valid_fd(fd)) {
|
||||
VDev *dev = (VDev *)(filemap[fd]->vdev);
|
||||
PX4_DEBUG("px4_read fd = %d", fd);
|
||||
ret = dev->read(filemap[fd], (char *)buffer, buflen);
|
||||
}
|
||||
else {
|
||||
ret = -EINVAL;
|
||||
}
|
||||
if (ret < 0) {
|
||||
px4_errno = -ret;
|
||||
ret = PX4_ERROR;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
ssize_t px4_write(int fd, const void *buffer, size_t buflen)
|
||||
{
|
||||
int ret;
|
||||
if (valid_fd(fd)) {
|
||||
VDev *dev = (VDev *)(filemap[fd]->vdev);
|
||||
PX4_DEBUG("px4_write fd = %d", fd);
|
||||
ret = dev->write(filemap[fd], (const char *)buffer, buflen);
|
||||
}
|
||||
else {
|
||||
ret = -EINVAL;
|
||||
}
|
||||
if (ret < 0) {
|
||||
px4_errno = -ret;
|
||||
ret = PX4_ERROR;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
int px4_ioctl(int fd, int cmd, unsigned long arg)
|
||||
{
|
||||
PX4_DEBUG("px4_ioctl fd = %d", fd);
|
||||
int ret = 0;
|
||||
if (valid_fd(fd)) {
|
||||
VDev *dev = (VDev *)(filemap[fd]->vdev);
|
||||
ret = dev->ioctl(filemap[fd], cmd, arg);
|
||||
}
|
||||
else {
|
||||
ret = -EINVAL;
|
||||
}
|
||||
if (ret < 0) {
|
||||
px4_errno = -ret;
|
||||
}
|
||||
|
||||
return (ret == 0) ? PX4_OK : PX4_ERROR;
|
||||
}
|
||||
|
||||
int px4_poll(px4_pollfd_struct_t *fds, nfds_t nfds, int timeout)
|
||||
{
|
||||
sem_t sem;
|
||||
int count = 0;
|
||||
int ret;
|
||||
unsigned int i;
|
||||
struct timespec ts;
|
||||
|
||||
PX4_DEBUG("Called px4_poll timeout = %d", timeout);
|
||||
sem_init(&sem, 0, 0);
|
||||
|
||||
// For each fd
|
||||
for (i=0; i<nfds; ++i)
|
||||
{
|
||||
fds[i].sem = &sem;
|
||||
fds[i].revents = 0;
|
||||
fds[i].priv = NULL;
|
||||
|
||||
// If fd is valid
|
||||
if (valid_fd(fds[i].fd))
|
||||
{
|
||||
VDev *dev = (VDev *)(filemap[fds[i].fd]->vdev);;
|
||||
PX4_DEBUG("px4_poll: VDev->poll(setup) %d", fds[i].fd);
|
||||
ret = dev->poll(filemap[fds[i].fd], &fds[i], true);
|
||||
|
||||
if (ret < 0)
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (ret >= 0)
|
||||
{
|
||||
if (timeout >= 0)
|
||||
{
|
||||
pthread_t pt;
|
||||
void *res;
|
||||
|
||||
ts.tv_sec = timeout/1000;
|
||||
ts.tv_nsec = (timeout % 1000)*1000;
|
||||
|
||||
// Create a timer to unblock
|
||||
struct timerData td(sem, ts);
|
||||
int rv = pthread_create(&pt, NULL, timer_handler, (void *)&td);
|
||||
if (rv != 0) {
|
||||
count = -1;
|
||||
goto cleanup;
|
||||
}
|
||||
sem_wait(&sem);
|
||||
|
||||
// Make sure timer thread is killed before sem goes
|
||||
// out of scope
|
||||
(void)pthread_cancel(pt);
|
||||
(void)pthread_join(pt, &res);
|
||||
}
|
||||
else
|
||||
{
|
||||
sem_wait(&sem);
|
||||
}
|
||||
|
||||
// For each fd
|
||||
for (i=0; i<nfds; ++i)
|
||||
{
|
||||
// If fd is valid
|
||||
if (valid_fd(fds[i].fd))
|
||||
{
|
||||
VDev *dev = (VDev *)(filemap[fds[i].fd]->vdev);;
|
||||
PX4_DEBUG("px4_poll: VDev->poll(teardown) %d", fds[i].fd);
|
||||
ret = dev->poll(filemap[fds[i].fd], &fds[i], false);
|
||||
|
||||
if (ret < 0)
|
||||
break;
|
||||
|
||||
if (fds[i].revents)
|
||||
count += 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
cleanup:
|
||||
sem_destroy(&sem);
|
||||
|
||||
return count;
|
||||
}
|
||||
|
||||
int px4_fsync(int fd)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
void px4_show_devices()
|
||||
{
|
||||
VDev::showDevices();
|
||||
}
|
||||
|
||||
void px4_show_topics()
|
||||
{
|
||||
VDev::showTopics();
|
||||
}
|
||||
|
||||
void px4_show_files()
|
||||
{
|
||||
VDev::showFiles();
|
||||
}
|
||||
|
||||
const char * px4_get_device_names(unsigned int *handle)
|
||||
{
|
||||
return VDev::devList(handle);
|
||||
}
|
||||
|
||||
const char * px4_get_topic_names(unsigned int *handle)
|
||||
{
|
||||
return VDev::topicList(handle);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -0,0 +1,65 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2015 Mark Charlebois. 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 vdev_file.cpp
|
||||
* Virtual file
|
||||
*
|
||||
* @author Mark Charlebois <charlebm@gmail.com>
|
||||
*/
|
||||
|
||||
#include "vfile.h"
|
||||
#include <stdio.h>
|
||||
|
||||
using namespace device;
|
||||
|
||||
VFile::VFile(const char *fname, mode_t mode) :
|
||||
VDev("vfile", fname)
|
||||
{
|
||||
}
|
||||
|
||||
VFile * VFile::createFile(const char *fname, mode_t mode)
|
||||
{
|
||||
VFile *me = new VFile(fname, mode);
|
||||
me->register_driver(fname, me);
|
||||
return me;
|
||||
}
|
||||
|
||||
ssize_t VFile::write(device::file_t *handlep, const char *buffer, size_t buflen)
|
||||
{
|
||||
// ignore what was written, but let pollers know something was written
|
||||
poll_notify(POLLIN);
|
||||
|
||||
return buflen;
|
||||
}
|
||||
|
||||
@@ -0,0 +1,58 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2015 Mark Charlebois. 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 vfile.cpp
|
||||
* Virtual file
|
||||
*
|
||||
* @author Mark Charlebois <charlebm@gmail.com>
|
||||
*/
|
||||
|
||||
#include <px4_tasks.h>
|
||||
#include <drivers/drv_device.h>
|
||||
#include "device.h"
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
|
||||
class VFile : public device::VDev {
|
||||
public:
|
||||
|
||||
static VFile *createFile(const char *fname, mode_t mode);
|
||||
~VFile() {}
|
||||
|
||||
virtual ssize_t write(device::file_t *handlep, const char *buffer, size_t buflen);
|
||||
|
||||
private:
|
||||
VFile(const char *fname, mode_t mode);
|
||||
VFile(const VFile &);
|
||||
};
|
||||
@@ -94,7 +94,7 @@ ORB_DECLARE(sensor_accel);
|
||||
*/
|
||||
|
||||
#define _ACCELIOCBASE (0x2100)
|
||||
#define _ACCELIOC(_n) (_IOC(_ACCELIOCBASE, _n))
|
||||
#define _ACCELIOC(_n) (_PX4_IOC(_ACCELIOCBASE, _n))
|
||||
|
||||
|
||||
/** set the accel internal sample rate to at least (arg) Hz */
|
||||
|
||||
@@ -59,7 +59,7 @@
|
||||
*/
|
||||
|
||||
#define _AIRSPEEDIOCBASE (0x7700)
|
||||
#define __AIRSPEEDIOC(_n) (_IOC(_AIRSPEEDIOCBASE, _n))
|
||||
#define __AIRSPEEDIOC(_n) (_PX4_IOC(_AIRSPEEDIOCBASE, _n))
|
||||
|
||||
#define AIRSPEEDIOCSSCALE __AIRSPEEDIOC(0)
|
||||
#define AIRSPEEDIOCGSCALE __AIRSPEEDIOC(1)
|
||||
|
||||
@@ -40,6 +40,7 @@
|
||||
#ifndef _DRV_BARO_H
|
||||
#define _DRV_BARO_H
|
||||
|
||||
#include <px4_defines.h>
|
||||
#include <stdint.h>
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
@@ -71,7 +72,7 @@ ORB_DECLARE(sensor_baro);
|
||||
*/
|
||||
|
||||
#define _BAROIOCBASE (0x2200)
|
||||
#define _BAROIOC(_n) (_IOC(_BAROIOCBASE, _n))
|
||||
#define _BAROIOC(_n) (_PX4_IOC(_BAROIOCBASE, _n))
|
||||
|
||||
/** set corrected MSL pressure in pascals */
|
||||
#define BAROIOCSMSLPRESSURE _BAROIOC(0)
|
||||
|
||||
@@ -42,6 +42,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <px4_defines.h>
|
||||
#include <stdint.h>
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
@@ -52,7 +53,7 @@
|
||||
*/
|
||||
|
||||
#define _BLINKMIOCBASE (0x2900)
|
||||
#define _BLINKMIOC(_n) (_IOC(_BLINKMIOCBASE, _n))
|
||||
#define _BLINKMIOC(_n) (_PX4_IOC(_BLINKMIOCBASE, _n))
|
||||
|
||||
/** play the named script in *(char *)arg, repeating forever */
|
||||
#define BLINKM_PLAY_SCRIPT_NAMED _BLINKMIOC(1)
|
||||
|
||||
@@ -51,7 +51,7 @@
|
||||
*/
|
||||
|
||||
#define _DEVICEIOCBASE (0x100)
|
||||
#define _DEVICEIOC(_n) (_IOC(_DEVICEIOCBASE, _n))
|
||||
#define _DEVICEIOC(_n) (_PX4_IOC(_DEVICEIOCBASE, _n))
|
||||
|
||||
/** ask device to stop publishing */
|
||||
#define DEVIOCSPUBBLOCK _DEVICEIOC(0)
|
||||
@@ -65,5 +65,8 @@
|
||||
*/
|
||||
#define DEVIOCGDEVICEID _DEVICEIOC(2)
|
||||
|
||||
#ifdef __PX4_POSIX
|
||||
#define DIOC_GETPRIV SIOCDEVPRIVATE
|
||||
#endif
|
||||
|
||||
#endif /* _DRV_DEVICE_H */
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user