\n'
image_name = image_path + image_name
- result += '

\n' % (image_name)
+ result += '

\n' % (image_name)
# check if all outputs are equal for the group: if so, show them
# only once
- outputs_prev = ['', ''] # split into MAINx and others (AUXx)
- outputs_match = [True, True]
+ all_outputs = {}
+ num_configs = len(group.GetParams())
for param in group.GetParams():
if not self.IsExcluded(param, board):
- outputs_current = ['', '']
for output_name in param.GetOutputCodes():
value = param.GetOutputValue(output_name)
- if output_name.lower().startswith('main'):
- idx = 0
- else:
- idx = 1
- outputs_current[idx] += '
%s: %s' % (output_name, value)
- for i in range(2):
- if len(outputs_current[i]) != 0:
- if outputs_prev[i] == '':
- outputs_prev[i] = outputs_current[i]
- elif outputs_current[i] != outputs_prev[i]:
- outputs_match[i] = False
-
- for i in range(2):
- if len(outputs_prev[i]) == 0:
- outputs_match[i] = False
- if not outputs_match[i]:
- outputs_prev[i] = ''
-
- if outputs_match[0] or outputs_match[1]:
- result += '
\n'
- result += ' \n'
+ key_value_pair = (output_name, value)
+ if key_value_pair not in all_outputs:
+ all_outputs[key_value_pair] = 0
+ all_outputs[key_value_pair] += 1
+ has_common_outputs = any(all_outputs[k] == num_configs for k in all_outputs)
+
+ if has_common_outputs:
+ outputs_common = ''.join(['{:}: {:}'.format(k[0], k[1]) \
+ for k in all_outputs if all_outputs[k] == num_configs])
+ result += '\n'
result += ' \n'
result += ' Common Outputs |
\n'
result += ' \n'
- result += '\n'
- result += '\n | \n
\n' % (outputs_prev[0], outputs_prev[1])
+ result += ' \n'
+ result += '\n | \n
\n' % (outputs_common)
result += '
\n'
result += '\n\n'
- result += '\n'
- result += ' \n'
+ result += '\n'
+ result += '
\n'
result += ' \n'
result += ' Name | |
\n'
result += ' \n'
@@ -90,10 +113,12 @@ def __init__(self, groups, board, image_path):
maintainer = param.GetMaintainer()
maintainer_entry = ''
if maintainer != '':
- maintainer_entry = 'Maintainer: %s
' % (html.escape(maintainer))
+ maintainer_entry = 'Maintainer: %s' % (html.escape(maintainer))
url = param.GetFieldValue('url')
- name_anchor='id="%s_%s_%s"' % (group.GetClass(),group.GetName(),name)
+ name_anchor='%s_%s_%s' % (group.GetClass(),group.GetName(),name)
name_anchor=name_anchor.replace(' ','_').lower()
+ name_anchor=name_anchor.replace('"','_').lower()
+ name_anchor='id="%s"' % name_anchor
name_entry = name
if url != '':
name_entry = '%s' % (url, name)
@@ -102,11 +127,8 @@ def __init__(self, groups, board, image_path):
for output_name in param.GetOutputCodes():
value = param.GetOutputValue(output_name)
valstrs = value.split(";")
- if output_name.lower().startswith('main'):
- idx = 0
- else:
- idx = 1
- if not outputs_match[idx]:
+ key_value_pair = (output_name, value)
+ if all_outputs[key_value_pair] < num_configs:
outputs += '%s: %s' % (output_name, value)
has_outputs = True
@@ -120,13 +142,13 @@ def __init__(self, groups, board, image_path):
else:
outputs_entry = ''
- result += ('\n %s | \n %s%s%s | \n\n
\n' %
+ result += ('\n %s | \n %s%s%s | \n
\n' %
(name_anchor, name_entry, maintainer_entry, airframe_id_entry,
outputs_entry))
#Close the table.
- result += '
\n\n'
+ result += '\n
\n\n\n'
self.output = result
diff --git a/Tools/px4airframes/rcout.py b/Tools/px4airframes/rcout.py
index 330c0793aba8..302cbf012d59 100644
--- a/Tools/px4airframes/rcout.py
+++ b/Tools/px4airframes/rcout.py
@@ -74,6 +74,7 @@ def __init__(self, groups, board, post_start=False):
result += "\n"
result += "if [ ${AIRFRAME} != none ]\n"
result += "then\n"
+ result += "\techo \"Loading airframe: /etc/init.d/airframes/${AIRFRAME}\"\n"
result += "\t. /etc/init.d/airframes/${AIRFRAME}\n"
if not post_start:
result += "else\n"
diff --git a/Tools/px4airframes/srcparser.py b/Tools/px4airframes/srcparser.py
index 6a8a8bcd4ad6..2fd314d67f02 100644
--- a/Tools/px4airframes/srcparser.py
+++ b/Tools/px4airframes/srcparser.py
@@ -98,6 +98,8 @@ def GetImageName(self):
return "Boat"
elif (self.name == "Balloon"):
return "Balloon"
+ elif (self.name == "Vectored 6 DOF UUV"):
+ return "Vectored6DofUUV"
return "AirframeUnknown"
def GetParams(self):
diff --git a/Tools/px4events/jsonout.py b/Tools/px4events/jsonout.py
new file mode 100644
index 000000000000..7e5affb08aed
--- /dev/null
+++ b/Tools/px4events/jsonout.py
@@ -0,0 +1,57 @@
+import codecs
+import json
+import sys
+import os
+
+
+class JsonOutput():
+ def __init__(self, groups):
+ all_json = {}
+ all_json['version'] = 1
+ component = {}
+ all_json['components'] = {1: component} #1: autopilot component
+
+ all_events = {}
+ component['namespace'] = "px4"
+ component['event_groups'] = all_events
+
+ for group in groups:
+ current_group = {}
+ current_events = {}
+ current_group['events'] = current_events
+ all_events[group] = current_group
+
+ for e in groups[group]:
+ event_obj = {}
+ event_obj['name'] = e.name
+ event_obj['message'] = e.message
+ if e.description is not None:
+ event_obj['description'] = e.description
+ args = []
+ for i in range(len(e.arguments)):
+ arg = {}
+ arg['type'] = e.arguments[i][0]
+ arg['name'] = e.arguments[i][1]
+ args.append(arg)
+ if len(args) > 0:
+ event_obj['arguments'] = args
+ sub_id = e.sub_id
+ assert sub_id not in current_events, \
+ "Duplicate event ID for {0} (message: '{1}'), other event message: '{2}'".format(
+ e.name, e.message, current_events[sub_id]['message'])
+ current_events[sub_id] = event_obj
+
+ self.json = all_json
+
+ def save(self, filename):
+ need_to_write = True
+ # only write if current file is not the same, to avoid updating the file
+ # timestamp
+ if os.path.isfile(filename):
+ with open(filename, 'rb') as json_file:
+ existing_data = json.load(json_file)
+ if existing_data == self.json:
+ need_to_write = False
+ if need_to_write:
+ with codecs.open(filename, 'w', 'utf-8') as f:
+ f.write(json.dumps(self.json,indent=2))
diff --git a/Tools/px4events/srcparser.py b/Tools/px4events/srcparser.py
new file mode 100644
index 000000000000..7a6c643ccaba
--- /dev/null
+++ b/Tools/px4events/srcparser.py
@@ -0,0 +1,309 @@
+import sys
+import re
+import math
+
+def hash_32_fnv1a(data: str):
+ hash_val = 0x811c9dc5
+ prime = 0x1000193
+ for i in range(len(data)):
+ value = ord(data[i])
+ hash_val = hash_val ^ value
+ hash_val *= prime
+ hash_val &= 0xffffffff
+ return hash_val
+
+
+class Event(object):
+ """
+ Single event definition
+ """
+
+ def __init__(self):
+ self.name = None
+ self.message = None
+ self.description = None
+ self.group = "default"
+ self._arguments = []
+
+ @staticmethod
+ def _get_id(name):
+ return 0xffffff & hash_32_fnv1a(name)
+
+ @property
+ def arguments(self):
+ """ list of (type: str, name: str) tuples """
+ return self._arguments
+
+ def set_default_arguments(self, num_args):
+ """ set argument names to default (if not specified) """
+ for i in range(num_args):
+ self.add_argument(None, "arg"+str(i))
+
+ def _shift_printed_arguments(self, msg, offset):
+ """ shift all { arguments by an offset """
+ i = 0
+ while i < len(msg):
+
+ if msg[i] == '\\': # escaped character
+ i += 2
+ continue
+
+ if msg[i] == '{':
+ m = re.match(r"^(\d+)", msg[i+1:])
+ if m:
+ arg_idx = int(m.group(1)) + offset
+ msg = msg[:i+1] + str(arg_idx) + msg[i+1+len(m.group(1)):]
+ i += 1
+ return msg
+
+ def prepend_arguments(self, arguments):
+ """ prepend additional arguments, and shift all '{}' in the
+ description and message
+ :param arguments: list of (type: str, name: str) tuples
+ """
+ self._arguments = arguments + self._arguments
+ num_added = len(arguments)
+ if self.message is not None:
+ self.message = self._shift_printed_arguments(self.message, num_added)
+ if self.description is not None:
+ self.description = self._shift_printed_arguments(self.description, num_added)
+
+ def add_argument(self, arg_type, name):
+ self._arguments.append((arg_type, name))
+
+ @property
+ def sub_id(self):
+ return self._get_id(self.name)
+
+ def validate(self):
+ if self.name is None: raise Exception("missing event name")
+ if self.message is None: raise Exception("missing event message for {}".format(self.name))
+ # just to ensure a common convention
+ assert self.message[-1] != '.', "Avoid event message ending in '.' ({:})".format(self.message)
+ # description is optional
+
+class SourceParser(object):
+ """
+ Parses provided data and stores all found events internally.
+ """
+
+ re_split_lines = re.compile(r'[\r\n]+')
+ re_comment_start = re.compile(r'^\/\*\s*EVENT$')
+ re_events_send = re.compile(r'^events::send[<\(]')
+ re_comment_content = re.compile(r'^\*\s*(.*)')
+ re_comment_tag = re.compile(r'^@([a-zA-Z][a-zA-Z0-9_]*):?\s*(.*)')
+ re_comment_end = re.compile(r'(.*?)\s*\*\/$')
+ re_code_end = re.compile(r'(.*?)\s*;$')
+ re_template_args = re.compile(r'([a-zA-Z0-9_:\.]+)\s*<([a-zA-Z0-9_,\s:]+)\s*>\s*\((.*)\);$')
+ re_no_template_args = re.compile(r'([a-zA-Z0-9_:\.]+)\s*\((.*)\);$')
+ re_event_id = re.compile(r'(events::)?ID\("([a-zA-Z0-9_]+)\"')
+
+ def __init__(self):
+ self._events = {}
+
+ @property
+ def events(self):
+ """ dict of 'group': [Event] list """
+ return self._events
+
+ def Parse(self, contents):
+ """
+ Incrementally parse program contents and append all found events
+ to the list.
+ """
+ # This code is essentially a comment-parsing grammar. "state"
+ # represents parser state. It contains human-readable state
+ # names.
+ state = None
+ def finalize_current_tag(event, tag, value):
+ if tag is None: return
+ if tag == "description":
+ descr = value.strip()
+ # merge continued lines (but not e.g. enumerations)
+ for i in range(1, len(descr)-1):
+ if descr[i-1] != '\n' and descr[i] == '\n' and descr[i+1].isalpha():
+ descr = descr[:i] + ' ' + descr[i+1:]
+ event.description = descr
+ elif tag == "group":
+ known_groups = ["calibration", "health", "arming_check", "normal"]
+ event.group = value.strip()
+ if not event.group in known_groups:
+ raise Exception("Unknown event group: '{}'\nKnown groups: {}\n" \
+ "If this is not a typo, add the new group to the script".format(event.group, known_groups))
+ elif tag.startswith("arg"):
+ arg_index = int(tag[3:])-1
+ arg_name = value.strip()
+ assert len(event.arguments) == arg_index, "Invalid argument ordering/duplicate ({}, {})".format(tag, value)
+ event.add_argument(None, arg_name)
+ else:
+ raise Exception("Invalid tag: {}\nvalue: {}".format(tag, value))
+
+ for line in self.re_split_lines.split(contents):
+ line = line.strip()
+ # Ignore empty lines
+ if line == "":
+ continue
+
+ assert not line.startswith("using namespace events;"), "Avoid 'using namespace events;', as it prevents proper events extraction"
+
+ # Check for '/* EVENT'
+ if self.re_comment_start.match(line):
+ state = "parse-comments"
+ event = Event()
+ current_tag = None
+ current_value = None
+ current_code = ""
+ continue
+
+ # Check for events::send (allow '/* EVENT' to be optional)
+ if state is None and self.re_events_send.match(line):
+ state = "parse-command"
+ event = Event()
+ current_tag = None
+ current_value = None
+ current_code = ""
+
+ if state is None:
+ assert 'events::ID(' not in line or line.startswith('//'), \
+ "unmatched 'events::ID(' found in line '{:}'".format(line)
+ continue
+
+ if state == "parse-command":
+ current_code += line
+ m = self.re_code_end.search(line)
+ if m:
+ # extract template arguments
+ m = self.re_template_args.search(current_code)
+ if m:
+ call, template_args, args = m.group(1, 2, 3)
+ template_args = template_args.split(',')
+ else:
+ m = self.re_no_template_args.search(current_code)
+ if m:
+ template_args = []
+ call, args = m.group(1, 2)
+ else:
+ raise Exception("Failed to parse code line {:}".format(current_code))
+
+ # if event arguments are not specified, use default naming
+ if len(event.arguments) == 0:
+ event.set_default_arguments(len(template_args))
+
+ # get argument types from template arguments
+ assert len(template_args) == len(event.arguments), \
+ "Number of arguments mismatch (args: {:})".format(template_args)
+ num_args = len(template_args)
+ for i in range(num_args):
+ arg_name = event.arguments[i][1]
+ arg_type = template_args[i].strip()
+ if arg_type.startswith('events::'):
+ arg_type = arg_type[8:]
+ arg_type = arg_type.replace('enums::', '')
+ event.arguments[i] = (arg_type, arg_name)
+ #print("method: {}, args: {}, template args: {}".format(call, args, event.arguments))
+
+ ignore_event = False
+
+ # extract function arguments
+ args_split = self._parse_arguments(args)
+ if call == "events::send" or call == "send":
+ if len(args_split) == 1:
+ # This is a send call for a generated event
+ ignore_event = True
+ else:
+ assert len(args_split) == num_args + 3, \
+ "Unexpected Number of arguments for: {:}, " \
+ "num template args: {:} (missing template args?)" \
+ .format(args_split, num_args)
+ m = self.re_event_id.search(args_split[0])
+ if m:
+ _, event_name = m.group(1, 2)
+ else:
+ raise Exception("Could not extract event ID from {:}".format(args_split[0]))
+ event.name = event_name
+ # unescape \x, to treat the string the same as the C++ compiler
+ event.message = args_split[2][1:-1].encode("utf-8").decode('unicode_escape')
+ elif call in ['reporter.healthFailure', 'reporter.armingCheckFailure']:
+ assert len(args_split) == num_args + 5, \
+ "Unexpected Number of arguments for: {:}, {:}".format(args_split, num_args)
+ m = self.re_event_id.search(args_split[2])
+ if m:
+ _, event_name = m.group(1, 2)
+ else:
+ raise Exception("Could not extract event ID from {:}".format(args_split[2]))
+ event.name = event_name
+ event.message = args_split[4][1:-1]
+ if 'health' in call:
+ event.group = "health"
+ else:
+ event.group = "arming_check"
+ event.prepend_arguments([('common::navigation_mode_category_t', 'modes'),
+ ('uint8_t', 'health_component_index')])
+ else:
+ raise Exception("unknown event method call: {}, args: {}".format(call, args))
+
+ if not ignore_event:
+ event.validate()
+
+ # insert
+ if not event.group in self._events:
+ self._events[event.group] = []
+ self._events[event.group].append(event)
+
+ state = None
+
+ else: # parse-comments
+ m = self.re_comment_end.search(line)
+ if m:
+ line = m.group(1)
+ last_comment_line = True
+ else:
+ last_comment_line = False
+ m = self.re_comment_content.match(line)
+ if m:
+ comment_content = m.group(1)
+ m = self.re_comment_tag.match(comment_content)
+ if m:
+ finalize_current_tag(event, current_tag, current_value)
+ current_tag, current_value = m.group(1, 2)
+ elif current_tag is not None:
+ current_value += "\n"+comment_content
+ # else: empty line before any tag
+ elif not last_comment_line:
+ # Invalid comment line (inside comment, but not starting with
+ # "*" or "*/".
+ raise Exception("Excpected a comment, got '{}'".format(line))
+ if last_comment_line:
+ finalize_current_tag(event, current_tag, current_value)
+ state = "parse-command"
+ return True
+
+ def _parse_arguments(self, args):
+ """
+ given a string of arguments, returns a list of strings split into the
+ arguments, with respecting brackets.
+ args is expected to be a single line.
+ Note: comments are not handled, also template arguments.
+
+ e.g. "32, test(4,4), \"e(c\", ab" -> ["32", "test(4,4)", "\"e(c\"", "ab"]
+ """
+ args_split = []
+ start = 0
+ bracket = 0
+ in_string = False
+ for i in range(len(args)):
+ if in_string and args[i] == "\"" and args[i-1] != "\\":
+ in_string = False
+ elif not in_string and args[i] == "\"":
+ in_string = True
+ if in_string:
+ continue
+ if args[i] in "{([":
+ bracket += 1
+ if args[i] in "})]":
+ bracket -= 1
+ if bracket == 0 and args[i] == ',':
+ args_split.append(args[start:i].strip())
+ start = i + 1
+ args_split.append(args[start:].strip())
+ return args_split
diff --git a/Tools/px4events/srcscanner.py b/Tools/px4events/srcscanner.py
new file mode 100644
index 000000000000..3f14fb949d75
--- /dev/null
+++ b/Tools/px4events/srcscanner.py
@@ -0,0 +1,52 @@
+import os
+import re
+import codecs
+import sys
+
+class SourceScanner(object):
+ """
+ Traverses directory tree, reads all source files, and passes their contents
+ to the Parser.
+ """
+
+ def ScanDir(self, srcdirs, parser):
+ """
+ Scans provided path and passes all found contents to the parser using
+ parser.Parse method.
+ """
+ extensions = tuple([".cpp"])
+ for srcdir in srcdirs:
+ if os.path.isfile(srcdir):
+ if not self.ScanFile(srcdir, parser):
+ return False
+ else:
+ for dirname, dirnames, filenames in os.walk(srcdir):
+ for filename in filenames:
+ if filename.endswith(extensions):
+ path = os.path.join(dirname, filename)
+ try:
+ if not self.ScanFile(path, parser):
+ return False
+ except:
+ print(("Exception in file %s" % path))
+ raise
+ return True
+
+ def ScanFile(self, path, parser):
+ """
+ Scans provided file and passes its contents to the parser using
+ parser.Parse method.
+ """
+
+ with codecs.open(path, 'r', 'utf-8') as f:
+ try:
+ contents = f.read()
+ except:
+ contents = ''
+ print('Failed reading file: %s, skipping content.' % path)
+ pass
+ try:
+ return parser.Parse(contents)
+ except Exception as e:
+ print("Exception while parsing file {}".format(path))
+ raise
diff --git a/Tools/px4moduledoc/markdownout.py b/Tools/px4moduledoc/markdownout.py
index 2b8dbbba3edf..9896c091b4ec 100644
--- a/Tools/px4moduledoc/markdownout.py
+++ b/Tools/px4moduledoc/markdownout.py
@@ -28,7 +28,7 @@ def __init__(self, module_groups):
Since this is generated from source, errors must be reported/fixed
in the [PX4-Autopilot](https://github.com/PX4/PX4-Autopilot) repository.
The documentation pages can be generated by running the following command from
-the root of the Firmware directory:
+the root of the PX4-Autopilot directory:
```
make module_documentation
```
@@ -66,7 +66,7 @@ def _ProcessModules(self, module_list):
result = ''
for module in module_list:
result += "## %s\n" % module.name()
- result += "Source: [%s](https://github.com/PX4/Firmware/tree/master/src/%s)\n\n" % (module.scope(), module.scope())
+ result += "Source: [%s](https://github.com/PX4/PX4-Autopilot/tree/master/src/%s)\n\n" % (module.scope(), module.scope())
doc = module.documentation()
if len(doc) > 0:
result += "%s\n" % doc
diff --git a/Tools/px4moduledoc/srcparser.py b/Tools/px4moduledoc/srcparser.py
index 1f42123b4c2b..b843a235f1f4 100644
--- a/Tools/px4moduledoc/srcparser.py
+++ b/Tools/px4moduledoc/srcparser.py
@@ -14,9 +14,9 @@ class ModuleDocumentation(object):
# If you add categories or subcategories, they also need to be added to the
# TOC in https://github.com/PX4/Devguide/blob/master/en/SUMMARY.md
valid_categories = ['driver', 'estimator', 'controller', 'system',
- 'communication', 'command', 'template', 'simulation']
+ 'communication', 'command', 'template', 'simulation', 'autotune']
valid_subcategories = ['', 'distance_sensor', 'imu', 'airspeed_sensor',
- 'magnetometer', 'baro', 'optical_flow']
+ 'magnetometer', 'baro', 'optical_flow', 'rpm_sensor', 'transponder']
max_line_length = 80 # wrap lines that are longer than this
@@ -137,8 +137,8 @@ def _handle_usage_params_i2c_spi_driver(self, args):
"\"board-specific bus (default=all) (external SPI: n-th bus (default=1))\"", 'true'])
if self._is_bool_true(args[1]):
- self._handle_usage_param_int(['\'c\'', '1', '1', '10',
- "\"chip-select index (for external SPI)\"", 'true'])
+ self._handle_usage_param_int(['\'c\'', '-1', '0', '31',
+ "\"chip-select pin (for internal SPI) or index (for external SPI)\"", 'true'])
self._handle_usage_param_int(['\'m\'', '-1', '0', '3', "\"SPI mode\"", 'true'])
self._handle_usage_param_int(['\'f\'', '-1', '0', '1000000', "\"bus frequency in kHz\"", 'true'])
diff --git a/Tools/px_process_events.py b/Tools/px_process_events.py
new file mode 100755
index 000000000000..66e9aaa52910
--- /dev/null
+++ b/Tools/px_process_events.py
@@ -0,0 +1,102 @@
+#!/usr/bin/env python
+############################################################################
+#
+# Copyright (C) 2020 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# PX4 events processor (main executable file)
+#
+# This tool scans the PX4 source code for definitions of events.
+#
+
+import sys
+import os
+import argparse
+from px4events import srcscanner, srcparser, jsonout
+
+import re
+import codecs
+
+
+def main():
+ # Parse command line arguments
+ parser = argparse.ArgumentParser(description="Process events definitions.")
+ parser.add_argument("-s", "--src-path",
+ default=["../src"],
+ metavar="PATH",
+ nargs='*',
+ help="one or more paths/files to source files to scan for events")
+ parser.add_argument("-j", "--json",
+ nargs='?',
+ const="events.json",
+ metavar="FILENAME",
+ help="Create Json output file"
+ " (default FILENAME: events.json)")
+ parser.add_argument('-v', '--verbose',
+ action='store_true',
+ help="verbose output")
+
+ args = parser.parse_args()
+
+ # Check for valid command
+ if not (args.json):
+ print("Error: You need to specify at least one output method!")
+ parser.print_usage()
+ sys.exit(1)
+
+ # Initialize source scanner and parser
+ scanner = srcscanner.SourceScanner()
+ parser = srcparser.SourceParser()
+
+ # Scan directories, and parse the files
+ if args.verbose:
+ print("Scanning source path/files " + str(args.src_path))
+
+ # canonicalize + remove duplicates
+ src_paths = set()
+ for path in args.src_path:
+ src_paths.add(os.path.realpath(path))
+
+ if not scanner.ScanDir(src_paths, parser):
+ sys.exit(1)
+
+ events = parser.events
+
+ # Output to JSON file
+ if args.json:
+ if args.verbose: print("Creating Json file " + args.json)
+ cur_dir = os.path.dirname(os.path.realpath(__file__))
+ out = jsonout.JsonOutput(events)
+ out.save(args.json)
+
+if __name__ == "__main__":
+ main()
diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py
index aa25560a6404..b35e5bc372bf 100755
--- a/Tools/px_uploader.py
+++ b/Tools/px_uploader.py
@@ -56,7 +56,6 @@
import sys
import argparse
import binascii
-import serial
import socket
import struct
import json
@@ -68,6 +67,16 @@
from sys import platform as _platform
+try:
+ import serial
+except ImportError as e:
+ print("Failed to import serial: " + str(e))
+ print("")
+ print("You may need to install it using:")
+ print(" pip3 install --user pyserial")
+ print("")
+ sys.exit(1)
+
# Detect python version
if sys.version_info[0] < 3:
runningPython3 = False
@@ -673,7 +682,28 @@ def __next_baud_flightstack(self):
return True
- def send_reboot(self):
+ def send_protocol_splitter_format(self, data):
+ # Header Structure:
+ # bits: 1 2 3 4 5 6 7 8
+ # header[0] - | Magic | (='S')
+ # header[1] - |T| LenH | (T - 0: mavlink; 1: rtps)
+ # header[2] - | LenL |
+ # header[3] - | Checksum |
+
+ MAGIC = 83
+
+ len_bytes = len(data).to_bytes(2, "big")
+ LEN_H = len_bytes[0] & 127
+ LEN_L = len_bytes[1] & 255
+ CHECKSUM = MAGIC ^ LEN_H ^ LEN_L
+
+ header_ints = [MAGIC, LEN_H, LEN_L, CHECKSUM]
+ header_bytes = struct.pack("{}B".format(len(header_ints)), *header_ints)
+
+ self.__send(header_bytes)
+ self.__send(data)
+
+ def send_reboot(self, use_protocol_splitter_format=False):
if (not self.__next_baud_flightstack()):
return False
@@ -684,15 +714,19 @@ def send_reboot(self):
print("If the board does not respond, unplug and re-plug the USB connector.", file=sys.stderr)
try:
+ send_fct = self.__send
+ if use_protocol_splitter_format:
+ send_fct = self.send_protocol_splitter_format
+
# try MAVLINK command first
self.port.flush()
- self.__send(uploader.MAVLINK_REBOOT_ID1)
- self.__send(uploader.MAVLINK_REBOOT_ID0)
+ send_fct(uploader.MAVLINK_REBOOT_ID1)
+ send_fct(uploader.MAVLINK_REBOOT_ID0)
# then try reboot via NSH
- self.__send(uploader.NSH_INIT)
- self.__send(uploader.NSH_REBOOT_BL)
- self.__send(uploader.NSH_INIT)
- self.__send(uploader.NSH_REBOOT)
+ send_fct(uploader.NSH_INIT)
+ send_fct(uploader.NSH_REBOOT_BL)
+ send_fct(uploader.NSH_INIT)
+ send_fct(uploader.NSH_REBOOT)
self.port.flush()
self.port.baudrate = self.baudrate_bootloader
except Exception:
@@ -717,38 +751,19 @@ def main():
parser.add_argument('--baud-flightstack', action="store", default="57600", help="Comma-separated list of baud rate of the serial port (default is 57600) when communicating with flight stack (Mavlink or NSH), only required for true serial ports.")
parser.add_argument('--force', action='store_true', default=False, help='Override board type check, or silicon errata checks and continue loading')
parser.add_argument('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash')
+ parser.add_argument('--use-protocol-splitter-format', action='store_true', help='use protocol splitter format for reboot')
parser.add_argument('firmware', action="store", help="Firmware file to be uploaded")
args = parser.parse_args()
+ if args.use_protocol_splitter_format:
+ print("Using protocol splitter format to reboot pixhawk!")
+
# warn people about ModemManager which interferes badly with Pixhawk
if os.path.exists("/usr/sbin/ModemManager"):
print("==========================================================================================================")
print("WARNING: You should uninstall ModemManager as it conflicts with any non-modem serial device (like Pixhawk)")
print("==========================================================================================================")
- # We need to check for pyserial because the import itself doesn't
- # seem to fail, at least not on macOS.
- pyserial_installed = False
- try:
- if serial.__version__:
- pyserial_installed = True
- except:
- pass
-
- try:
- if serial.VERSION:
- pyserial_installed = True
- except:
- pass
-
- if not pyserial_installed:
- print("Error: pyserial not installed!")
- print("")
- print("You may need to install it using:")
- print(" pip3 install --user pyserial")
- print("")
- sys.exit(1)
-
# Load the firmware file
fw = firmware(args.firmware)
@@ -844,7 +859,7 @@ def main():
except Exception:
- if not up.send_reboot():
+ if not up.send_reboot(args.use_protocol_splitter_format):
break
# wait for the reboot, without we might run into Serial I/O Error 5
diff --git a/Tools/serial/generate_config.py b/Tools/serial/generate_config.py
index 27003b904bba..84a9c342aad4 100755
--- a/Tools/serial/generate_config.py
+++ b/Tools/serial/generate_config.py
@@ -1,8 +1,6 @@
#!/usr/bin/env python3
""" Script to generate Serial (UART) parameters and the ROMFS startup script """
-from __future__ import print_function
-
import argparse
import os
import sys
@@ -138,6 +136,12 @@
"default_baudrate": 1, # set default to an unusable value to detect that this serial port has not been configured
},
+ # Pixhawk Payload Bus
+ "PPB": {
+ "label": "Pixhawk Payload Bus",
+ "index": 401,
+ "default_baudrate": 57600,
+ },
}
@@ -189,8 +193,6 @@
# parse the YAML files
serial_commands = []
ethernet_configuration = []
-additional_params = ""
-additional_ethernet_params = ""
if ethernet_supported:
ethernet_configuration.append({
@@ -211,161 +213,12 @@ def parse_yaml_serial_config(yaml_config):
ret.append(serial_config)
return ret
-def parse_yaml_parameters_config(yaml_config):
- """ parse the parameters section from the yaml config file """
- if 'parameters' not in yaml_config:
- return ''
- parameters_section_list = yaml_config['parameters']
- for parameters_section in parameters_section_list:
- if 'definitions' not in parameters_section:
- return ''
- definitions = parameters_section['definitions']
- ret = ''
- param_group = parameters_section.get('group', None)
- for param_name in definitions:
- param = definitions[param_name]
- if 'ethernet' in param:
- continue
- num_instances = param.get('num_instances', 1)
- instance_start = param.get('instance_start', 0) # offset
-
- # get the type and extract all tags
- tags = '@group {:}'.format(param_group)
- if param['type'] == 'enum':
- param_type = 'INT32'
- for key in param['values']:
- tags += '\n * @value {:} {:}'.format(key, param['values'][key])
- elif param['type'] == 'boolean':
- param_type = 'INT32'
- tags += '\n * @boolean'
- elif param['type'] == 'int32':
- param_type = 'INT32'
- elif param['type'] == 'float':
- param_type = 'FLOAT'
- else:
- raise Exception("unknown param type {:}".format(param['type']))
-
- for tag in ['decimal', 'increment', 'category', 'volatile', 'bit',
- 'min', 'max', 'unit', 'reboot_required']:
- if tag in param:
- tags += '\n * @{:} {:}'.format(tag, param[tag])
-
- for i in range(num_instances):
- # default value
- default_value = 0
- if 'default' in param:
- # default can be a list of num_instances or a single value
- if type(param['default']) == list:
- assert len(param['default']) == num_instances
- default_value = param['default'][i]
- else:
- default_value = param['default']
-
- if type(default_value) == bool:
- default_value = int(default_value)
-
- # output the existing C-style format
- ret += '''
-/**
- * {short_descr}
- *
- * {long_descr}
- *
- * {tags}
- */
-PARAM_DEFINE_{param_type}({name}, {default_value});
-'''.format(short_descr=param['description']['short'].replace("\n", "\n * "),
- long_descr=param['description']['long'].replace("\n", "\n * "),
- tags=tags,
- param_type=param_type,
- name=param_name,
- default_value=default_value,
- ).replace('${i}', str(i+instance_start))
- return ret
-
-def parse_yaml_ethernet_parameters_config(yaml_config):
- """ parse the parameters section from the yaml config file """
- if 'parameters' not in yaml_config:
- return ''
- parameters_section_list = yaml_config['parameters']
- for parameters_section in parameters_section_list:
- if 'definitions' not in parameters_section:
- return ''
- definitions = parameters_section['definitions']
- ret = ''
- param_group = parameters_section.get('group', None)
- for param_name in definitions:
- param = definitions[param_name]
- if 'ethernet' not in param:
- continue
- num_instances = param.get('num_instances', 1)
- instance_start = param.get('instance_start', 0) # offset
-
- # get the type and extract all tags
- tags = '@group {:}'.format(param_group)
- if param['type'] == 'enum':
- param_type = 'INT32'
- for key in param['values']:
- tags += '\n * @value {:} {:}'.format(key, param['values'][key])
- elif param['type'] == 'boolean':
- param_type = 'INT32'
- tags += '\n * @boolean'
- elif param['type'] == 'int32':
- param_type = 'INT32'
- elif param['type'] == 'float':
- param_type = 'FLOAT'
- else:
- raise Exception("unknown param type {:}".format(param['type']))
-
- for tag in ['decimal', 'increment', 'category', 'volatile', 'bit',
- 'min', 'max', 'unit', 'reboot_required']:
- if tag in param:
- tags += '\n * @{:} {:}'.format(tag, param[tag])
-
- for i in range(num_instances):
- # default value
- default_value = 0
- if 'default' in param:
- # default can be a list of num_instances or a single value
- if type(param['default']) == list:
- assert len(param['default']) == num_instances
- default_value = param['default'][i]
- else:
- default_value = param['default']
-
- if type(default_value) == bool:
- default_value = int(default_value)
-
- # output the existing C-style format
- ret += '''
-/**
- * {short_descr}
- *
- * {long_descr}
- *
- * {tags}
- */
-PARAM_DEFINE_{param_type}({name}, {default_value});
-'''.format(short_descr=param['description']['short'].replace("\n", "\n * "),
- long_descr=param['description']['long'].replace("\n", "\n * "),
- tags=tags,
- param_type=param_type,
- name=param_name,
- default_value=default_value,
- ).replace('${i}', str(i+instance_start))
- return ret
-
for yaml_file in args.config_files:
with open(yaml_file, 'r') as stream:
try:
yaml_config = yaml.load(stream, Loader=yaml.Loader)
serial_commands.extend(parse_yaml_serial_config(yaml_config))
- # TODO: additional params should be parsed in a separate script
- additional_params += parse_yaml_parameters_config(yaml_config)
- if ethernet_supported:
- additional_ethernet_params += parse_yaml_ethernet_parameters_config(yaml_config)
-
except yaml.YAMLError as exc:
print(exc)
raise
@@ -415,10 +268,14 @@ def parse_yaml_ethernet_parameters_config(yaml_config):
default_port_str = port_config['default'][i]
else:
default_port_str = port_config['default']
+
if default_port_str != "":
if default_port_str not in serial_ports:
raise Exception("Default Port {:} not found for {:}".format(default_port_str, serial_command['label']))
- default_port = serial_ports[default_port_str]['index']
+
+ if default_port_str in dict(board_ports).keys():
+ default_port = serial_ports[default_port_str]['index']
+
commands.append({
'command': serial_command['command'],
@@ -429,7 +286,7 @@ def parse_yaml_ethernet_parameters_config(yaml_config):
'default_port': default_port,
'param_group': port_config['group'],
'description_extended': port_config.get('description_extended', ''),
- 'ethernet_config': serial_command.get('ethernet', 'none')
+ 'supports_networking': serial_command.get('supports_networking', False)
})
if verbose:
@@ -472,7 +329,5 @@ def parse_yaml_ethernet_parameters_config(yaml_config):
with open(serial_params_output_file, 'w') as fid:
fid.write(template.render(serial_devices=serial_devices,
ethernet_configuration=ethernet_configuration,
- commands=commands, serial_ports=serial_ports,
- additional_definitions=additional_params,
- additional_ethernet_definitions=additional_ethernet_params))
+ commands=commands, serial_ports=serial_ports))
diff --git a/Tools/serial/rc.serial_port.jinja b/Tools/serial/rc.serial_port.jinja
index c3f7c9651e18..087732176148 100644
--- a/Tools/serial/rc.serial_port.jinja
+++ b/Tools/serial/rc.serial_port.jinja
@@ -17,9 +17,9 @@ if param compare "$PRT" {{ serial_device.index }}; then
fi
{% endfor %}
+
{% for config in ethernet_configuration -%}
if param compare "$PRT" {{ config.index }}; then
set SERIAL_DEV ethernet
fi
-
{% endfor %}
diff --git a/Tools/serial/serial_params.c.jinja b/Tools/serial/serial_params.c.jinja
index 4bed33a2c96d..13cee1e896ea 100644
--- a/Tools/serial/serial_params.c.jinja
+++ b/Tools/serial/serial_params.c.jinja
@@ -58,10 +58,11 @@ PARAM_DEFINE_INT32(SER_{{ serial_device.tag }}_BAUD, {{ serial_device.default_ba
{%- for serial_device in serial_devices %}
* @value {{ serial_device.index }} {{ serial_device.label }}
{%- endfor %}
-{%- if command.ethernet_config != "none" %}
+{%- if command.supports_networking %}
{%- for config in ethernet_configuration %}
* @value {{ config.index }} {{ config.label }}
-{%- endfor %}{% endif %}
+{%- endfor %}
+{%- endif %}
* @group {{ command.param_group }}
* @reboot_required true
*/
@@ -70,7 +71,3 @@ PARAM_DEFINE_INT32({{ command.port_param_name }}, {{ command.default_port }});
{% endfor -%}
{% endif %}
-{{ additional_definitions }}
-
-{{ additional_ethernet_definitions }}
-
diff --git a/Tools/setup/arch.sh b/Tools/setup/arch.sh
old mode 100644
new mode 100755
index 79d44496dce9..83bc225d495b
--- a/Tools/setup/arch.sh
+++ b/Tools/setup/arch.sh
@@ -48,7 +48,6 @@ echo "Installing PX4 general dependencies"
sudo pacman -Sy --noconfirm --needed \
astyle \
base-devel \
- ccache \
clang \
cmake \
cppcheck \
@@ -155,8 +154,7 @@ if [[ $INSTALL_SIM == "true" ]]; then
# fix VMWare 3D graphics acceleration for gazebo
exportline="export SVGA_VGPU10=0"
- if grep -Fxq "$exportline" $HOME/.profile; then
- else
+ if !grep -Fxq "$exportline" $HOME/.profile; then
echo $exportline >> $HOME/.profile;
fi
fi
diff --git a/Tools/setup/macos.sh b/Tools/setup/macos.sh
index b0afb431f3c1..5133b66af033 100755
--- a/Tools/setup/macos.sh
+++ b/Tools/setup/macos.sh
@@ -33,6 +33,7 @@ if [[ $REINSTALL_FORMULAS == "--reinstall" ]]; then
brew tap PX4/px4
brew reinstall px4-dev
+ brew install ncurses
else
if brew ls --versions px4-dev > /dev/null; then
echo "px4-dev already installed"
@@ -40,12 +41,13 @@ else
echo "Installing PX4 general dependencies (homebrew px4-dev)"
brew tap PX4/px4
brew install px4-dev
+ brew install ncurses
fi
fi
# Python dependencies
echo "Installing PX4 Python3 dependencies"
-pip3 install --user -r ${DIR}/requirements.txt
+python3 -m pip install --user -r ${DIR}/requirements.txt
# Optional, but recommended additional simulation tools:
if [[ $INSTALL_SIM == "--sim-tools" ]]; then
diff --git a/Tools/setup/requirements.txt b/Tools/setup/requirements.txt
index f7e322d14fde..e84c676d7e9b 100644
--- a/Tools/setup/requirements.txt
+++ b/Tools/setup/requirements.txt
@@ -3,10 +3,14 @@ argparse>=1.2
cerberus
coverage
empy>=3.3
+future
jinja2>=2.8
+jsonschema
+kconfiglib
+lxml
matplotlib>=3.0.*
numpy>=1.13
-nunavut
+nunavut>=1.1.0
packaging
pandas>=0.21
pkgconfig
@@ -15,7 +19,7 @@ pygments
wheel>=0.31.1
pymavlink
pyros-genmsg
-pyserial>=3.0
+pyserial
pyulog>=0.5.0
pyyaml
requests
diff --git a/Tools/setup/shell.nix b/Tools/setup/shell.nix
index d3e77d3c47cc..0ade3f432af3 100644
--- a/Tools/setup/shell.nix
+++ b/Tools/setup/shell.nix
@@ -44,6 +44,7 @@ in pkgs.mkShell {
coverage
empy
jinja2
+ jsonschema
matplotlib
numpy
packaging
diff --git a/Tools/setup/ubuntu.sh b/Tools/setup/ubuntu.sh
index 933c77c46d0a..25c12cb170d8 100755
--- a/Tools/setup/ubuntu.sh
+++ b/Tools/setup/ubuntu.sh
@@ -1,5 +1,7 @@
#! /usr/bin/env bash
+set -e
+
## Bash script to setup PX4 development environment on Ubuntu LTS (20.04, 18.04, 16.04).
## Can also be used in docker.
##
@@ -75,7 +77,6 @@ sudo apt-get update -y --quiet
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
astyle \
build-essential \
- ccache \
cmake \
cppcheck \
file \
@@ -84,6 +85,8 @@ sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends i
gdb \
git \
lcov \
+ libxml2-dev \
+ libxml2-utils \
make \
ninja-build \
python3 \
@@ -97,16 +100,16 @@ sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends i
zip \
;
-if [[ "${UBUNTU_RELEASE}" == "16.04" ]]; then
- echo "Installing Ubuntu 16.04 PX4-compatible ccache version"
- wget -O /tmp/ccache_3.4.1-1_amd64.deb http://launchpadlibrarian.net/356662933/ccache_3.4.1-1_amd64.deb
- sudo dpkg -i /tmp/ccache_3.4.1-1_amd64.deb
-fi
-
# Python3 dependencies
echo
echo "Installing PX4 Python3 dependencies"
-python3 -m pip install --user -r ${DIR}/requirements.txt
+if [ -n "$VIRTUAL_ENV" ]; then
+ # virtual envrionments don't allow --user option
+ python -m pip install -r ${DIR}/requirements.txt
+else
+ # older versions of Ubuntu require --user option
+ python3 -m pip install --user -r ${DIR}/requirements.txt
+fi
# NuttX toolchain (arm-none-eabi-gcc)
if [[ $INSTALL_NUTTX == "true" ]]; then
@@ -115,20 +118,40 @@ if [[ $INSTALL_NUTTX == "true" ]]; then
echo "Installing NuttX dependencies"
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
- autoconf \
automake \
+ binutils-dev \
bison \
- bzip2 \
- file \
+ build-essential \
flex \
+ g++-multilib \
+ gcc-multilib \
gdb-multiarch \
+ genromfs \
+ gettext \
gperf \
- libncurses-dev \
+ libelf-dev \
+ libexpat-dev \
+ libgmp-dev \
+ libisl-dev \
+ libmpc-dev \
+ libmpfr-dev \
+ libncurses5 \
+ libncurses5-dev \
+ libncursesw5-dev \
libtool \
pkg-config \
screen \
+ texinfo \
+ u-boot-tools \
+ util-linux \
vim-common \
;
+ if [[ "${UBUNTU_RELEASE}" == "20.04" ]]; then
+ sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
+ kconfig-frontends \
+ ;
+ fi
+
if [ -n "$USER" ]; then
# add user to dialout group (serial port access)
@@ -177,13 +200,12 @@ if [[ $INSTALL_SIM == "true" ]]; then
if [[ "${UBUNTU_RELEASE}" == "18.04" ]]; then
java_version=11
- gazebo_version=9
elif [[ "${UBUNTU_RELEASE}" == "20.04" ]]; then
- java_version=14
- gazebo_version=11
+ java_version=13
+ elif [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then
+ java_version=11
else
java_version=14
- gazebo_version=11
fi
# Java (jmavsim or fastrtps)
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
@@ -197,20 +219,30 @@ if [[ $INSTALL_SIM == "true" ]]; then
sudo update-alternatives --set java $(update-alternatives --list java | grep "java-$java_version")
# Gazebo
+ if [[ "${UBUNTU_RELEASE}" == "18.04" ]]; then
+ gazebo_version=9
+ gazebo_packages="gazebo$gazebo_version libgazebo$gazebo_version-dev"
+ elif [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then
+ gazebo_packages="gazebo libgazebo-dev"
+ else
+ # default and Ubuntu 20.04
+ gazebo_version=11
+ gazebo_packages="gazebo$gazebo_version libgazebo$gazebo_version-dev"
+ fi
+
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
# Update list, since new gazebo-stable.list has been added
sudo apt-get update -y --quiet
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
dmidecode \
- gazebo$gazebo_version \
+ $gazebo_packages \
gstreamer1.0-plugins-bad \
gstreamer1.0-plugins-base \
gstreamer1.0-plugins-good \
gstreamer1.0-plugins-ugly \
gstreamer1.0-libav \
libeigen3-dev \
- libgazebo$gazebo_version-dev \
libgstreamer-plugins-base1.0-dev \
libimage-exiftool-perl \
libopencv-dev \
diff --git a/Tools/setup_ignition.bash b/Tools/setup_ignition.bash
new file mode 100644
index 000000000000..7def58d35848
--- /dev/null
+++ b/Tools/setup_ignition.bash
@@ -0,0 +1,23 @@
+#!/bin/bash
+#
+# Setup environment to make PX4 visible to Gazebo.
+#
+# Note, this is not necessary if using a ROS catkin workspace with the px4
+# package as the paths are exported.
+#
+# License: according to LICENSE.md in the root directory of the PX4 Firmware repository
+
+if [ "$#" != 2 ]; then
+ echo -e "usage: source setup_gazebo.bash src_dir build_dir\n"
+ return 1
+fi
+
+SRC_DIR=$1
+BUILD_DIR=$2
+
+# setup Gazebo env and update package path
+export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:${SRC_DIR}/build/px4_sitl_default/build_ign_gazebo
+export IGN_GAZEBO_SYSTEM_PLUGIN_PATH=$IGN_GAZEBO_SYSTEM_PLUGIN_PATH:${SRC_DIR}/build/px4_sitl_default/build_ign_gazebo
+export IGN_GAZEBO_RESOURCE_PATH=$IGN_GAZEBO_RESOURCE_PATH:${SRC_DIR}/Tools/simulation-ignition/models
+
+echo -e "LD_LIBRARY_PATH $LD_LIBRARY_PATH"
diff --git a/Tools/simulation-ignition b/Tools/simulation-ignition
new file mode 160000
index 000000000000..483193d9b8b8
--- /dev/null
+++ b/Tools/simulation-ignition
@@ -0,0 +1 @@
+Subproject commit 483193d9b8b89211c3b970c735b4fbb5f724b63a
diff --git a/Tools/sitl_gazebo b/Tools/sitl_gazebo
index 3e5fed04d8e5..5610c3fb441a 160000
--- a/Tools/sitl_gazebo
+++ b/Tools/sitl_gazebo
@@ -1 +1 @@
-Subproject commit 3e5fed04d8e574b10e17e446d2938346bc6152ca
+Subproject commit 5610c3fb441a2f3babc8ad7a63c8c4ce3e40abfa
diff --git a/Tools/sitl_run.sh b/Tools/sitl_run.sh
index 9f36364ab22d..1ae1267b3df7 100755
--- a/Tools/sitl_run.sh
+++ b/Tools/sitl_run.sh
@@ -56,6 +56,13 @@ else
follow_mode=""
fi
+# To use gazebo_ros ROS2 plugins
+if [[ -n "$ROS_VERSION" ]] && [ "$ROS_VERSION" == "2" ]; then
+ ros_args="-s libgazebo_ros_init.so -s libgazebo_ros_factory.so"
+else
+ ros_args=""
+fi
+
if [ "$program" == "jmavsim" ]; then
jmavsim_pid=`ps aux | grep java | grep "\-jar jmavsim_run.jar" | awk '{ print $2 }'`
if [ -n "$jmavsim_pid" ]; then
@@ -67,6 +74,9 @@ if [ "$model" == "" ] || [ "$model" == "none" ]; then
if [ "$program" == "jsbsim" ]; then
echo "empty model, setting rascal as default for jsbsim"
model="rascal"
+ elif [ "$program" == "sihsim" ]; then
+ echo "empty model, setting quadx as default for sihsim"
+ model="quadx"
else
echo "empty model, setting iris as default"
model="iris"
@@ -133,7 +143,7 @@ elif [ "$program" == "gazebo" ] && [ ! -n "$no_sim" ]; then
world_path="$PX4_SITL_WORLD"
fi
fi
- gzserver $verbose $world_path &
+ gzserver $verbose $world_path $ros_args &
SIM_PID=$!
# Check all paths in ${GAZEBO_MODEL_PATH} for specified model
@@ -177,6 +187,15 @@ elif [ "$program" == "gazebo" ] && [ ! -n "$no_sim" ]; then
echo "You need to have gazebo simulator installed!"
exit 1
fi
+elif [ "$program" == "ignition" ] && [ -z "$no_sim" ]; then
+ echo "Ignition Gazebo"
+ if [[ -n "$HEADLESS" ]]; then
+ ignition_headless="-s"
+ else
+ ignition_headless=""
+ fi
+ source "$src_path/Tools/setup_ignition.bash" "${src_path}" "${build_path}"
+ ign gazebo --force-version 5 ${verbose} ${ignition_headless} -r "${src_path}/Tools/simulation-ignition/worlds/${model}.world"&
elif [ "$program" == "flightgear" ] && [ -z "$no_sim" ]; then
echo "FG setup"
cd "${src_path}/Tools/flightgear_bridge/"
@@ -198,6 +217,12 @@ elif [ "$program" == "jsbsim" ] && [ -z "$no_sim" ]; then
fi
"${build_path}/build_jsbsim_bridge/jsbsim_bridge" ${model} -s "${src_path}/Tools/jsbsim_bridge/scene/${world}.xml" 2> /dev/null &
JSBSIM_PID=$!
+elif [ "$program" == "sihsim" ] && [ ! -n "$no_sim" ]; then
+ export SIM_MODE="sihsim"
+ if [ "$model" != "airplane" ] && [ "$model" != "quadx" ] && [ "$model" != "xvert" ]; then
+ echo "Model ${model} not compatible with with sih. sih supports [quadx,airplane,xvert]."
+ exit 1
+ fi
fi
pushd "$rootfs" >/dev/null
diff --git a/Tools/test_keys/key0.pub b/Tools/test_keys/key0.pub
new file mode 100644
index 000000000000..86153ac96535
--- /dev/null
+++ b/Tools/test_keys/key0.pub
@@ -0,0 +1,5 @@
+//Public key to verify signed binaries
+0x4d, 0xb0, 0xc2, 0x1, 0x5, 0x55, 0x2a, 0x3c,
+0xd7, 0xfb, 0xaf, 0x5c, 0xba, 0x7a, 0xb0, 0x81,
+0x1b, 0x36, 0x63, 0xdb, 0x28, 0x52, 0x5e, 0xdb,
+0x14, 0x36, 0xf2, 0x57, 0x8d, 0x2, 0xb7, 0xfd,
diff --git a/Tools/test_keys/rsa2048.pem b/Tools/test_keys/rsa2048.pem
new file mode 100644
index 000000000000..e2ee0e61bfde
--- /dev/null
+++ b/Tools/test_keys/rsa2048.pem
@@ -0,0 +1,27 @@
+-----BEGIN RSA PRIVATE KEY-----
+MIIEowIBAAKCAQEAz6O47E+sN+Yb+h6zkukagzYtJ6ZKq344b5N6H2CDg6z9LmG/
+GRAfOeNstsz1hXyyOCcUQ9f+vKHofTN0k+fWKy95h1mwY5Vc509gRsmpD96pNp4+
+NLp3GFDjawOTqsfyLQ7zKwU0YKT3qeI3o20n2KNxnGuyXt0SK3Ph2530wwzWBR2s
+pNxpKvV8MCR7K4AbeuxodxKXKrLl0v9BHfUGpLZHpfoFfvChuK3eXK4si06tr6xt
+RmLh6f6hxcn0SNKAK+WpPsH8mN4DqayGt7UZ5XVqY4M/J3pe+PFtstI2ocDSX5Oc
+kOg+yonXytDH6I9Lt2CSXjZDcCM2+7WlBprAywIDAQABAoIBAGZE1nUV/NX/cXIt
+IvdN9q//xBfOUOLMpVFXSwQfTkdRsdXhcPUQOsERYd9bbeZUd5cusE2GGkKgYFki
+Od4LhzH4DRx8MWOrEnofX2UeODXHzoJHSI5B9Ry14n034shv+Lj2rxBWXOjo987l
+y8+jmMecIP4REWal7igWyHyZ/Q7/5UCCCH5HaA4jgMhMdrD3zdxrlPhrW/egjfKF
+Q+444qG5HzUqh7tOBxvf9Yu9FujHC9NxKDNXZZ3WBpwVQIVPCxexb4b8FBZ4syCH
+iPbSgyw91CVfMvpWCYqDe7ubw4QDLHzDIiyKFtvHmIOgPo74y8fi1YYZ+3dy5mpa
+UNdC11kCgYEA3whbNd71AVcSykRZ23AxDcjtUoiFXlpzSFes0QBGrmi2WTc04r8d
+5Zr1E8oohc/zPJnUnCh93BAAu+HJsg4wKCqOWu5qR3NWcFp4/4voG9hsg1hgWD8Z
+6fMMjoZRezSxadyeeaDStnfSkYyE2J8DPpkK5mjFG9IbrylGfApzDf0CgYEA7lTi
+j2NQ+HNMlp/oOtsRZHkQtHYutv5SltG4E4DlwDHyA2ZLR2xB+D2ce5VdPQvfHu8F
+ioMquDLeJbOPeikwko+RmpbmCsODjLueZHBmGwAfkuE0A5TZUwTi+W6iYbrXLK6E
+TgNMaS4AGeBbioo6cdnMnYp9jdm63zvefet6oGcCgYAwr4BJmCvfaQR/BsCeuDTd
+D3lOxOJoIFJ9/jWJQggr1kvH2dc/j/yUvGi3My/5VdWA6wuQMv6WZR/j43vF1HcK
+rY95pgWpJzI9QGKdVgsK2QmG+mm9mbisaxPYoNV0kaIQu8oUPtkAX9OlVglByCRL
+K9lHRqOQWSMV72qldRp8eQKBgHVCJkXN42SZtbDV8/ghGCmKtwFStCEsd43kmOBf
+pqos6JlrltYJGVv9VCQplLoYQSqDBwLjDf2aaVm7QngkE9XH9SdN3tik4PA4zvEz
+q8jVArPNQT4R2erSmKmIGTRkLMG7CzUmwk1taHdSvzcmUyL4uYc5QBSubxat6gWh
++a85AoGBAKgfnjjVoAWWvqEDLpfGPmE8lW+RaS7i5ff6QsSBx7uTEnHq6RNHuVnN
+et4pR87yIENeG8jMBiDCj8AGDtUNt9Ps9vWCPrf9HSOYoBUk+gZagU/9N+RBpuCM
+egoxtxIHM7HI+XIer+ZnZpVpgr+EoCaL7avx6k/susLQb7tqSBt1
+-----END RSA PRIVATE KEY-----
\ No newline at end of file
diff --git a/Tools/test_keys/rsa2048.pub b/Tools/test_keys/rsa2048.pub
new file mode 100644
index 000000000000..57dfa81ce303
--- /dev/null
+++ b/Tools/test_keys/rsa2048.pub
@@ -0,0 +1,38 @@
+
+0x30, 0x82, 0x1, 0x22, 0x30, 0xd, 0x6, 0x9,
+0x2a, 0x86, 0x48, 0x86, 0xf7, 0xd, 0x1, 0x1,
+0x1, 0x5, 0x0, 0x3, 0x82, 0x1, 0xf, 0x0,
+0x30, 0x82, 0x1, 0xa, 0x2, 0x82, 0x1, 0x1,
+0x0, 0xcf, 0xa3, 0xb8, 0xec, 0x4f, 0xac, 0x37,
+0xe6, 0x1b, 0xfa, 0x1e, 0xb3, 0x92, 0xe9, 0x1a,
+0x83, 0x36, 0x2d, 0x27, 0xa6, 0x4a, 0xab, 0x7e,
+0x38, 0x6f, 0x93, 0x7a, 0x1f, 0x60, 0x83, 0x83,
+0xac, 0xfd, 0x2e, 0x61, 0xbf, 0x19, 0x10, 0x1f,
+0x39, 0xe3, 0x6c, 0xb6, 0xcc, 0xf5, 0x85, 0x7c,
+0xb2, 0x38, 0x27, 0x14, 0x43, 0xd7, 0xfe, 0xbc,
+0xa1, 0xe8, 0x7d, 0x33, 0x74, 0x93, 0xe7, 0xd6,
+0x2b, 0x2f, 0x79, 0x87, 0x59, 0xb0, 0x63, 0x95,
+0x5c, 0xe7, 0x4f, 0x60, 0x46, 0xc9, 0xa9, 0xf,
+0xde, 0xa9, 0x36, 0x9e, 0x3e, 0x34, 0xba, 0x77,
+0x18, 0x50, 0xe3, 0x6b, 0x3, 0x93, 0xaa, 0xc7,
+0xf2, 0x2d, 0xe, 0xf3, 0x2b, 0x5, 0x34, 0x60,
+0xa4, 0xf7, 0xa9, 0xe2, 0x37, 0xa3, 0x6d, 0x27,
+0xd8, 0xa3, 0x71, 0x9c, 0x6b, 0xb2, 0x5e, 0xdd,
+0x12, 0x2b, 0x73, 0xe1, 0xdb, 0x9d, 0xf4, 0xc3,
+0xc, 0xd6, 0x5, 0x1d, 0xac, 0xa4, 0xdc, 0x69,
+0x2a, 0xf5, 0x7c, 0x30, 0x24, 0x7b, 0x2b, 0x80,
+0x1b, 0x7a, 0xec, 0x68, 0x77, 0x12, 0x97, 0x2a,
+0xb2, 0xe5, 0xd2, 0xff, 0x41, 0x1d, 0xf5, 0x6,
+0xa4, 0xb6, 0x47, 0xa5, 0xfa, 0x5, 0x7e, 0xf0,
+0xa1, 0xb8, 0xad, 0xde, 0x5c, 0xae, 0x2c, 0x8b,
+0x4e, 0xad, 0xaf, 0xac, 0x6d, 0x46, 0x62, 0xe1,
+0xe9, 0xfe, 0xa1, 0xc5, 0xc9, 0xf4, 0x48, 0xd2,
+0x80, 0x2b, 0xe5, 0xa9, 0x3e, 0xc1, 0xfc, 0x98,
+0xde, 0x3, 0xa9, 0xac, 0x86, 0xb7, 0xb5, 0x19,
+0xe5, 0x75, 0x6a, 0x63, 0x83, 0x3f, 0x27, 0x7a,
+0x5e, 0xf8, 0xf1, 0x6d, 0xb2, 0xd2, 0x36, 0xa1,
+0xc0, 0xd2, 0x5f, 0x93, 0x9c, 0x90, 0xe8, 0x3e,
+0xca, 0x89, 0xd7, 0xca, 0xd0, 0xc7, 0xe8, 0x8f,
+0x4b, 0xb7, 0x60, 0x92, 0x5e, 0x36, 0x43, 0x70,
+0x23, 0x36, 0xfb, 0xb5, 0xa5, 0x6, 0x9a, 0xc0,
+0xcb, 0x2, 0x3, 0x1, 0x0, 0x1,
diff --git a/Tools/test_keys.json b/Tools/test_keys/test_keys.json
similarity index 100%
rename from Tools/test_keys.json
rename to Tools/test_keys/test_keys.json
diff --git a/Tools/uorb_graph/create.py b/Tools/uorb_graph/create.py
index 844e4df3d7b8..34ef4a42046d 100755
--- a/Tools/uorb_graph/create.py
+++ b/Tools/uorb_graph/create.py
@@ -23,7 +23,7 @@
help='Excluded path(s), can be specified multiple times',
default=[])
parser.add_argument('--merge-depends', action='store_true',
- help='Merge library topics inte the modules that depend on them.')
+ help='Merge library topics in the modules that depend on them.')
parser.add_argument('-v','--verbosity', action='count',
help='increase output verbosity; primarily for debugging; repeat for more detail',
default=0)
@@ -56,6 +56,21 @@ def get_N_colors(N, s=0.8, v=0.9):
hex_out.append("#"+"".join(map(lambda x: format(x, '02x'), rgb)))
return hex_out
+def topic_filename(topic):
+ MSG_PATH = 'msg/'
+
+ file_list = os.listdir(MSG_PATH)
+ msg_files = [file.replace('.msg', '') for file in file_list if file.endswith(".msg")]
+
+ if topic in msg_files:
+ return topic
+ else:
+ for msg_file in msg_files:
+ with open(f'{MSG_PATH}/{msg_file}.msg') as f:
+ ret = re.findall(f'^# TOPICS.*{topic}.*',f.read(),re.MULTILINE)
+ if len(ret) > 0:
+ return msg_file
+ return "no_file"
class PubSub(object):
""" Collects either publication or subscription information for nodes
@@ -422,6 +437,7 @@ def _extract_build_information(self, file_name, **kwargs):
found_module_def = False
found_module_depends = False
found_library_def = False
+ scope_added = False
for line in datafile:
if 'px4_add_module' in line: # must contain 'px4_add_module'
found_module_def = True
@@ -432,6 +448,7 @@ def _extract_build_information(self, file_name, **kwargs):
library_name = tokens[1].split()[0].strip().rstrip(')')
library_scope = LibraryScope(library_name)
self._current_scope.append(library_scope)
+ scope_added = True
self._found_libraries[library_name] = library_scope
if self._in_scope():
log.debug(' >> found library: ' + library_name)
@@ -443,16 +460,18 @@ def _extract_build_information(self, file_name, **kwargs):
elif found_module_depends:
# two tabs is a *sketchy* heuristic -- spacing isn't guaranteed by cmake;
# ... but the hard-tabs *is* specified by PX4 coding standards, so it's likely to be consistent
- if line.startswith('\t\t'):
+ if line.startswith('\t\t') and not line.strip().startswith('#'):
depends = [dep.strip() for dep in line.split()]
for name in depends:
+ log.debug(' >> {:}: found module dep: {:}'
+ .format(self._current_scope[-1].name, name))
self._current_scope[-1].add_dependency(name)
if kwargs['merge_depends']:
if (0 < len(self._scope_whitelist)) and self._current_scope[-1].name in self._scope_whitelist:
# if we whitelist a module with dependencies, whitelist the dependencies, too
self._scope_whitelist.add(name)
- else:
+ elif line.strip() != "":
found_module_depends = False ## done with the 'DEPENDS' section.
words = line.split()
@@ -461,17 +480,21 @@ def _extract_build_information(self, file_name, **kwargs):
module_name = words[1]
module_scope = ModuleScope(module_name)
self._current_scope.append(module_scope)
+ scope_added = True
self._found_modules[module_name] = module_scope
if self._in_scope():
log.debug(' >> Found module name: ' + module_scope.name)
- return (found_library_def or found_module_def)
+ return scope_added
def _process_source_file(self, file_name):
""" extract information from a single source file """
- log.debug( " >> extracting topics from file: " + file_name )
+ current_scope = self._get_current_scope()
+ log.debug( " >> {:}extracting topics from file: {:}"
+ .format(current_scope.name+": " if current_scope is not None else "",
+ file_name))
with codecs.open(file_name, 'r', 'utf-8') as f:
try:
@@ -481,7 +504,6 @@ def _process_source_file(self, file_name):
return
- current_scope = self._get_current_scope()
if current_scope:
if current_scope.name in self._scope_blacklist:
return
@@ -672,8 +694,7 @@ def write(self, file_name):
node['type'] = 'topic'
node['color'] = topic_colors[topic]
# url is opened when double-clicking on the node
- # TODO: does not work for multi-topics
- node['url'] = 'https://github.com/PX4/Firmware/blob/master/msg/'+topic+'.msg'
+ node['url'] = 'https://github.com/PX4/PX4-Autopilot/blob/master/msg/'+topic_filename(topic)+'.msg'
nodes.append(node)
data['nodes'] = nodes
diff --git a/Tools/update_px4_ros2_bridge.sh b/Tools/update_px4_ros2_bridge.sh
new file mode 100755
index 000000000000..58ebca5b7ce7
--- /dev/null
+++ b/Tools/update_px4_ros2_bridge.sh
@@ -0,0 +1,135 @@
+#!/usr/bin/env bash
+set -e
+
+agent_template_files_updated=0
+code_generator_files_updated=0
+
+# parse help argument
+if [[ $1 == "-h" ]] || [[ $1 == "--help" ]]; then
+ echo -e "Usage: update_px4_ros2_bridge.bash [options...] \t This script allows to update px4_ros_com and px4_msgs in a specified directory." >&2
+ echo
+ echo -e "\t--ws_dir \t\t Location of the ament/colcon workspace. Default: $HOME/colcon_ws."
+ echo -e "\t--px4_ros_com \t\t Updates px4_ros_com microRTPS agent code generation and templates."
+ echo -e "\t--px4_msgs \t\t Updates px4_msgs messages definition files."
+ echo -e "\t--all \t\t Updates both px4_ros_com and px4_msgs."
+ echo
+ exit 0
+fi
+
+# parse the arguments
+while [ $# -gt 0 ]; do
+ if [[ $1 == *"--"* ]]; then
+ v="${1/--/}"
+ if [ ! -z $2 ]; then
+ declare $v="$2"
+ else
+ declare $v=1
+ fi
+ fi
+ shift
+done
+
+# get script directory
+SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
+
+# get PX4-Autopilot directory
+PX4_DIR=$(cd "$(dirname "$SCRIPT_DIR")" && pwd)
+
+function compare_and_update () {
+ cmp -s "$1" "$2"
+ if [ $? -eq 1 ]; then
+ cp "$1" "$2"
+ return 0
+ fi
+
+ return 1;
+}
+
+# update microRTPS agent code generators / helpers
+function update_agent_code {
+ declare -a templates=( \
+ "microRTPS_agent.cpp.em" \
+ "microRTPS_timesync.cpp.em" \
+ "microRTPS_timesync.h.em" \
+ "microRTPS_transport.cpp" \
+ "microRTPS_transport.h" \
+ "Publisher.cpp.em" \
+ "Publisher.h.em" \
+ "Subscriber.cpp.em" \
+ "Subscriber.h.em" \
+ "RtpsTopics.cpp.em" \
+ "RtpsTopics.h.em" \
+ )
+
+ for file in ${templates[@]}; do
+ compare_and_update "$PX4_DIR/msg/templates/urtps/$file" "$ws_dir/src/px4_ros_com/templates/$file" \
+ && echo -e "--\t\t- '$ws_dir/src/px4_ros_com/templates/$file' updated" && ((agent_template_files_updated+=1))
+ done
+ if [ $agent_template_files_updated -eq 0 ]; then
+ echo -e "--\t\t- No template files updated"
+ elif [ $agent_template_files_updated -eq 1 ]; then
+ echo -e "--\t\t - 1 template file updated"
+ else
+ echo -e "--\t\t - $agent_template_files_updated template files updated"
+ fi
+}
+
+# update microRTPS agent code templates
+function update_agent_templates {
+ declare -a code_generators=( \
+ "uorb_rtps_classifier.py" \
+ "generate_microRTPS_bridge.py" \
+ "px_generate_uorb_topic_files.py" \
+ )
+ for file in ${code_generators[@]}; do
+ compare_and_update "$PX4_DIR/msg/tools/$file $ws_dir/src/px4_ros_com/scripts/$file" \
+ && echo -e "--\t\t- '$ws_dir/src/px4_ros_com/scripts/$file' updated" && ((code_generator_files_updated+=1))
+ done
+ if [ $code_generator_files_updated -eq 0 ]; then
+ echo -e "--\t\t- No code generators / helpers files updated"
+ elif [ $code_generator_files_updated -eq 1 ]; then
+ echo -e "--\t\t - 1 code generator / helper file updated"
+ else
+ echo -e "--\t\t - $code_generator_files_updated code generator / helper files updated"
+ fi
+}
+
+# update px4_ros_com files
+function update_px4_ros_com {
+ python3 $PX4_DIR/msg/tools/uorb_to_ros_urtps_topics.py -i $PX4_DIR/msg/tools/urtps_bridge_topics.yaml -o $ws_dir/src/px4_ros_com/templates/urtps_bridge_topics.yaml
+ echo -e "--------------- \033[1mmicroRTPS agent code generation and templates update\033[0m ----------------"
+ echo "-------------------------------------------------------------------------------------------------------"
+ update_agent_code
+ update_agent_templates
+ return 0
+}
+
+# function to update px4_msgs
+function update_px4_msgs {
+ find "$ws_dir/src/px4_msgs/msg/" -maxdepth 1 -type f -delete
+ python3 $PX4_DIR/msg/tools/uorb_to_ros_msgs.py $PX4_DIR/msg/ $ws_dir/src/px4_msgs/msg/
+}
+
+# decisor
+echo "-------------------------------------------------------------------------------------------------------"
+if [ -d "${ws_dir}" ]; then
+ ws_dir=$(cd "$ws_dir" && pwd)
+ if [ ! -z ${all} ]; then
+ update_px4_ros_com
+ echo "-------------------------------------------------------------------------------------------------------"
+ update_px4_msgs
+ elif [ ! -z ${px4_ros_com} ]; then
+ update_px4_ros_com
+ echo "-------------------------------------------------------------------------------------------------------"
+ elif [ ! -z ${px4_msgs} ]; then
+ update_px4_msgs
+ fi
+ echo -e "-------------------------------- \033[0;32mUpdate successful!\033[0m ---------------------------------"
+ echo "-------------------------------------------------------------------------------------------------------"
+ exit 0
+else
+ echo -e "-- \033[0;31mWorkspace directory doesn't exist...\033[0m"
+ echo -e "---------------------------------- \033[0;31mUpdate failed!\033[0m -----------------------------------"
+ echo "-------------------------------------------------------------------------------------------------------"
+ exit $ERRCODE
+fi
diff --git a/Tools/validate_json.py b/Tools/validate_json.py
index 98affc3d37e5..b80dad3198be 100755
--- a/Tools/validate_json.py
+++ b/Tools/validate_json.py
@@ -5,6 +5,7 @@
import argparse
import sys
import json
+import os
try:
from jsonschema import validate
@@ -21,6 +22,8 @@
parser.add_argument('json_file', nargs='+', help='JSON config file(s)')
parser.add_argument('--schema-file', type=str, action='store',
help='JSON schema file', required=True)
+parser.add_argument('--skip-if-no-schema', dest='skip_if_no_schema', action='store_true',
+ help='Skip test if schema file does not exist')
parser.add_argument('-v', '--verbose', dest='verbose', action='store_true',
help='Verbose Output')
@@ -29,6 +32,9 @@
json_files = args.json_file
verbose = args.verbose
+if args.skip_if_no_schema and not os.path.isfile(schema_file):
+ sys.exit(0)
+
# load the schema
with open(schema_file, 'r') as stream:
schema = json.load(stream)
diff --git a/boards/airmind/mindpx-v2/default.cmake b/boards/airmind/mindpx-v2/default.cmake
deleted file mode 100644
index 5ef2da1abb88..000000000000
--- a/boards/airmind/mindpx-v2/default.cmake
+++ /dev/null
@@ -1,133 +0,0 @@
-
-px4_add_board(
- PLATFORM nuttx
- VENDOR airmind
- MODEL mindpx-v2
- LABEL default
- TOOLCHAIN arm-none-eabi
- ARCHITECTURE cortex-m4
- CONSTRAINED_MEMORY
- ROMFSROOT px4fmu_common
- TESTING
- UAVCAN_INTERFACES 1
- SERIAL_PORTS
- GPS1:/dev/ttyS3
- TEL1:/dev/ttyS1
- TEL2:/dev/ttyS2
- DRIVERS
- adc/ads1115
- adc/board_adc
- barometer # all available barometer drivers
- batt_smbus
- camera_capture
- camera_trigger
- differential_pressure # all available differential pressure drivers
- distance_sensor # all available distance sensor drivers
- #dshot
- gps
- #heater
- #imu # all available imu drivers
- imu/l3gd20
- imu/lsm303d
- imu/invensense/mpu6000
- imu/invensense/mpu6500
- irlock
- lights # all available light drivers
- magnetometer # all available magnetometer drivers
- optical_flow # all available optical flow drivers
- osd
- pca9685
- pca9685_pwm_out
- power_monitor/ina226
- #protocol_splitter
- pwm_input
- pwm_out_sim
- pwm_out
- rc_input
- roboclaw
- rpm
- telemetry # all available telemetry drivers
- test_ppm
- tone_alarm
- uavcan
- MODULES
- airspeed_selector
- attitude_estimator_q
- battery_status
- camera_feedback
- commander
- dataman
- ekf2
- esc_battery
- events
- flight_mode_manager
- fw_att_control
- fw_pos_control_l1
- gyro_calibration
- gyro_fft
- land_detector
- landing_target_estimator
- load_mon
- local_position_estimator
- logger
- mavlink
- mc_att_control
- mc_hover_thrust_estimator
- mc_pos_control
- mc_rate_control
- #micrortps_bridge
- navigator
- rc_update
- rover_pos_control
- sensors
- sih
- temperature_compensation
- uuv_att_control
- uuv_pos_control
- vmount
- vtol_att_control
- SYSTEMCMDS
- bl_update
- #dmesg
- dumpfile
- esc_calib
- gpio
- hardfault_log
- i2cdetect
- led_control
- mft
- mixer
- motor_ramp
- motor_test
- mtd
- nshterm
- param
- perf
- pwm
- reboot
- reflect
- sd_bench
- serial_test
- system_time
- tests # tests and test runner
- top
- topic_listener
- tune_control
- uorb
- usb_connected
- ver
- work_queue
- EXAMPLES
- fake_gps
- fake_gyro
- fake_magnetometer
- fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
- hello
- hwtest # Hardware test
- #matlab_csv_serial
- px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
- px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
- rover_steering_control # Rover example app
- uuv_example_app
- work_item
- )
diff --git a/boards/airmind/mindpx-v2/default.px4board b/boards/airmind/mindpx-v2/default.px4board
new file mode 100644
index 000000000000..7b52a99b646d
--- /dev/null
+++ b/boards/airmind/mindpx-v2/default.px4board
@@ -0,0 +1,107 @@
+CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
+CONFIG_BOARD_ARCHITECTURE="cortex-m4"
+CONFIG_BOARD_CONSTRAINED_MEMORY=y
+CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
+CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
+CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
+CONFIG_DRIVERS_ADC_ADS1115=y
+CONFIG_DRIVERS_ADC_BOARD_ADC=y
+CONFIG_COMMON_BAROMETERS=y
+CONFIG_DRIVERS_BATT_SMBUS=y
+CONFIG_DRIVERS_CAMERA_CAPTURE=y
+CONFIG_DRIVERS_CAMERA_TRIGGER=y
+CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
+CONFIG_COMMON_DISTANCE_SENSOR=y
+CONFIG_DRIVERS_GPS=y
+CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
+CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
+CONFIG_DRIVERS_IMU_INVENSENSE_MPU6500=y
+CONFIG_DRIVERS_IMU_L3GD20=y
+CONFIG_DRIVERS_IMU_LSM303D=y
+CONFIG_DRIVERS_IRLOCK=y
+CONFIG_COMMON_LIGHT=y
+CONFIG_COMMON_MAGNETOMETER=y
+CONFIG_COMMON_OPTICAL_FLOW=y
+CONFIG_DRIVERS_OSD=y
+CONFIG_DRIVERS_PCA9685=y
+CONFIG_DRIVERS_PCA9685_PWM_OUT=y
+CONFIG_DRIVERS_POWER_MONITOR_INA226=y
+CONFIG_DRIVERS_PWM_INPUT=y
+CONFIG_DRIVERS_PWM_OUT=y
+CONFIG_DRIVERS_PWM_OUT_SIM=y
+CONFIG_DRIVERS_RC_INPUT=y
+CONFIG_DRIVERS_ROBOCLAW=y
+CONFIG_DRIVERS_RPM=y
+CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
+CONFIG_COMMON_TELEMETRY=y
+CONFIG_DRIVERS_TONE_ALARM=y
+CONFIG_DRIVERS_UAVCAN=y
+CONFIG_BOARD_UAVCAN_INTERFACES=1
+CONFIG_MODULES_AIRSPEED_SELECTOR=y
+CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
+CONFIG_MODULES_BATTERY_STATUS=y
+CONFIG_MODULES_CAMERA_FEEDBACK=y
+CONFIG_MODULES_COMMANDER=y
+CONFIG_MODULES_DATAMAN=y
+CONFIG_MODULES_EKF2=y
+CONFIG_MODULES_ESC_BATTERY=y
+CONFIG_MODULES_EVENTS=y
+CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
+CONFIG_MODULES_FW_ATT_CONTROL=y
+CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
+CONFIG_MODULES_FW_POS_CONTROL_L1=y
+CONFIG_MODULES_GYRO_CALIBRATION=y
+CONFIG_MODULES_GYRO_FFT=y
+CONFIG_MODULES_LAND_DETECTOR=y
+CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
+CONFIG_MODULES_LOAD_MON=y
+CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
+CONFIG_MODULES_LOGGER=y
+CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
+CONFIG_MODULES_MANUAL_CONTROL=y
+CONFIG_MODULES_MAVLINK=y
+CONFIG_MODULES_MC_ATT_CONTROL=y
+CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
+CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
+CONFIG_MODULES_MC_POS_CONTROL=y
+CONFIG_MODULES_MC_RATE_CONTROL=y
+CONFIG_MODULES_CONTROL_ALLOCATOR=y
+CONFIG_MODULES_NAVIGATOR=y
+CONFIG_MODULES_RC_UPDATE=y
+CONFIG_MODULES_ROVER_POS_CONTROL=y
+CONFIG_MODULES_SENSORS=y
+CONFIG_MODULES_SIH=y
+CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
+CONFIG_MODULES_UUV_ATT_CONTROL=y
+CONFIG_MODULES_UUV_POS_CONTROL=y
+CONFIG_MODULES_GIMBAL=y
+CONFIG_MODULES_VTOL_ATT_CONTROL=y
+CONFIG_SYSTEMCMDS_BL_UPDATE=y
+CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
+CONFIG_SYSTEMCMDS_DUMPFILE=y
+CONFIG_SYSTEMCMDS_GPIO=y
+CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
+CONFIG_SYSTEMCMDS_I2CDETECT=y
+CONFIG_SYSTEMCMDS_LED_CONTROL=y
+CONFIG_SYSTEMCMDS_MFT=y
+CONFIG_SYSTEMCMDS_MIXER=y
+CONFIG_SYSTEMCMDS_MOTOR_TEST=y
+CONFIG_SYSTEMCMDS_MTD=y
+CONFIG_SYSTEMCMDS_NSHTERM=y
+CONFIG_SYSTEMCMDS_PARAM=y
+CONFIG_SYSTEMCMDS_PERF=y
+CONFIG_SYSTEMCMDS_PWM=y
+CONFIG_SYSTEMCMDS_REBOOT=y
+CONFIG_SYSTEMCMDS_REFLECT=y
+CONFIG_SYSTEMCMDS_SD_BENCH=y
+CONFIG_SYSTEMCMDS_SD_STRESS=y
+CONFIG_SYSTEMCMDS_SERIAL_TEST=y
+CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
+CONFIG_SYSTEMCMDS_TOP=y
+CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
+CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
+CONFIG_SYSTEMCMDS_UORB=y
+CONFIG_SYSTEMCMDS_USB_CONNECTED=y
+CONFIG_SYSTEMCMDS_VER=y
+CONFIG_SYSTEMCMDS_WORK_QUEUE=y
+CONFIG_EXAMPLES_FAKE_GPS=y
diff --git a/boards/airmind/mindpx-v2/bootloader/airmind_mindpx-v2_bootloader.bin b/boards/airmind/mindpx-v2/extras/airmind_mindpx-v2_bootloader.bin
similarity index 100%
rename from boards/airmind/mindpx-v2/bootloader/airmind_mindpx-v2_bootloader.bin
rename to boards/airmind/mindpx-v2/extras/airmind_mindpx-v2_bootloader.bin
diff --git a/boards/airmind/mindpx-v2/init/rc.board_defaults b/boards/airmind/mindpx-v2/init/rc.board_defaults
new file mode 100644
index 000000000000..5d576dd74711
--- /dev/null
+++ b/boards/airmind/mindpx-v2/init/rc.board_defaults
@@ -0,0 +1,7 @@
+#!/bin/sh
+#
+# board specific defaults
+#------------------------------------------------------------------------------
+
+param set-default BAT1_V_DIV 10.177939394
+param set-default BAT1_A_PER_V 15.391030303
diff --git a/boards/airmind/mindpx-v2/init/rc.board_mavlink b/boards/airmind/mindpx-v2/init/rc.board_mavlink
deleted file mode 100644
index 76e6351fb08c..000000000000
--- a/boards/airmind/mindpx-v2/init/rc.board_mavlink
+++ /dev/null
@@ -1,7 +0,0 @@
-#!/bin/sh
-#
-# Airmind Mindpx-v2 specific board MAVLink startup script.
-#------------------------------------------------------------------------------
-
-# Start MAVLink on the USB port
-mavlink start -d /dev/ttyACM0
diff --git a/boards/airmind/mindpx-v2/nuttx-config/nsh/defconfig b/boards/airmind/mindpx-v2/nuttx-config/nsh/defconfig
index 19093de3c658..9f7d02d481d3 100644
--- a/boards/airmind/mindpx-v2/nuttx-config/nsh/defconfig
+++ b/boards/airmind/mindpx-v2/nuttx-config/nsh/defconfig
@@ -19,12 +19,13 @@
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
+# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_TIME is not set
# CONFIG_STM32_CCMEXCLUDE is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
-CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
+CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/airmind/mindpx-v2/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32"
@@ -41,6 +42,7 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
+CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0030
CONFIG_CDCACM_PRODUCTSTR="MindPX FMU v2.x"
CONFIG_CDCACM_RXBUFSIZE=600
@@ -90,18 +92,13 @@ CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
-CONFIG_NFILE_DESCRIPTORS=12
CONFIG_NSH_ARCHINIT=y
-CONFIG_NSH_ARCHROMFS=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_IFCONFIG=y
CONFIG_NSH_DISABLE_IFUPDOWN=y
-CONFIG_NSH_DISABLE_MB=y
-CONFIG_NSH_DISABLE_MH=y
-CONFIG_NSH_DISABLE_MW=y
CONFIG_NSH_DISABLE_TELNETD=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
@@ -117,7 +114,6 @@ CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_SETSPEED=y
-CONFIG_RAMTRON_WRITEWAIT=y
CONFIG_RAM_SIZE=262144
CONFIG_RAM_START=0x20000000
CONFIG_RAW_BINARY=y
@@ -134,8 +130,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDIO_BLOCKSETUP=y
-CONFIG_SEM_NNESTPRIO=8
-CONFIG_SEM_PREALLOCHOLDERS=0
+CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
@@ -178,7 +173,7 @@ CONFIG_STM32_SPI1=y
CONFIG_STM32_SPI2=y
CONFIG_STM32_SPI4=y
CONFIG_STM32_SPI4_DMA=y
-CONFIG_STM32_SPI4_DMA_BUFFER=1024
+CONFIG_STM32_SPI4_DMA_BUFFER=512
CONFIG_STM32_SPI_DMA=y
CONFIG_STM32_SPI_DMATHRESHOLD=8
CONFIG_STM32_TIM10=y
diff --git a/boards/airmind/mindpx-v2/src/board_config.h b/boards/airmind/mindpx-v2/src/board_config.h
index 0bb915f402eb..65d587f66ccc 100644
--- a/boards/airmind/mindpx-v2/src/board_config.h
+++ b/boards/airmind/mindpx-v2/src/board_config.h
@@ -72,12 +72,6 @@
#define ADC_RC_RSSI_CHANNEL 11
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
-/* Define Battery 1 Voltage Divider and A per V
- */
-
-#define BOARD_BATTERY1_V_DIV (10.177939394f)
-#define BOARD_BATTERY1_A_PER_V (15.391030303f)
-
/* Power supply control and monitoring GPIOs */
// #define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8)
// #define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
@@ -95,7 +89,6 @@
/* AUX PWMs
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 8
-#define DIRECT_INPUT_TIMER_CHANNELS 8
/* USB OTG FS
*
@@ -153,7 +146,6 @@
#define BOARD_ADC_PERIPH_5V_OC (0)
#define BOARD_ADC_HIPOWER_5V_OC (0)
-#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
diff --git a/boards/airmind/mindpx-v2/src/init.c b/boards/airmind/mindpx-v2/src/init.c
index 90415bceb50c..30a3e6a67900 100644
--- a/boards/airmind/mindpx-v2/src/init.c
+++ b/boards/airmind/mindpx-v2/src/init.c
@@ -53,6 +53,7 @@
#include
#include
#include
+#include
#include
#include
@@ -217,22 +218,11 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "DMA alloc FAILED\n");
}
- /* set up the serial DMA polling */
+#if defined(SERIAL_HAVE_RXDMA)
+ // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
- struct timespec ts;
-
- /*
- * Poll at 1ms intervals for received bytes that have not triggered
- * a DMA event.
- */
- ts.tv_sec = 0;
- ts.tv_nsec = 1000000;
-
- hrt_call_every(&serial_dma_call,
- ts_to_abstime(&ts),
- ts_to_abstime(&ts),
- (hrt_callout)stm32_serial_dma_poll,
- NULL);
+ hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
+#endif
/* initial LED state */
drv_led_start();
@@ -249,7 +239,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
if (!spi4) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 4\n");
board_autoled_on(LED_AMBER);
- return -ENODEV;
}
/* Default SPI4 to 10MHz and de-assert the known chip selects. */
@@ -265,7 +254,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
if (!spi1) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 1\n");
board_autoled_on(LED_AMBER);
- return -ENODEV;
}
/* Default SPI1 to 37.5 MHz (40 MHz rounded to nearest valid divider, F4 max)
@@ -289,9 +277,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
if (!sdio) {
- syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n",
- CONFIG_NSH_MMCSDSLOTNO);
- return -ENODEV;
+ syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", CONFIG_NSH_MMCSDSLOTNO);
}
/* Now bind the SDIO interface to the MMC/SD driver */
@@ -299,7 +285,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
if (ret != OK) {
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
- return ret;
}
/* Then let's guess and say that there is a card in the slot. There is no card detect GPIO. */
diff --git a/boards/ark/can-flow/canbootloader.cmake b/boards/ark/can-flow/canbootloader.cmake
deleted file mode 100644
index 1ca01c65a606..000000000000
--- a/boards/ark/can-flow/canbootloader.cmake
+++ /dev/null
@@ -1,13 +0,0 @@
-include (${CMAKE_CURRENT_LIST_DIR}/uavcan_board_identity)
-
-px4_add_board(
- PLATFORM nuttx
- VENDOR ark
- MODEL can-flow
- LABEL canbootloader
- TOOLCHAIN arm-none-eabi
- ARCHITECTURE cortex-m4
- CONSTRAINED_MEMORY
- DRIVERS
- bootloaders
-)
diff --git a/boards/ark/can-flow/canbootloader.px4board b/boards/ark/can-flow/canbootloader.px4board
new file mode 100644
index 000000000000..46917280f6a4
--- /dev/null
+++ b/boards/ark/can-flow/canbootloader.px4board
@@ -0,0 +1,5 @@
+CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
+CONFIG_BOARD_ARCHITECTURE="cortex-m4"
+CONFIG_BOARD_ROMFSROOT=""
+CONFIG_BOARD_CONSTRAINED_MEMORY=y
+CONFIG_DRIVERS_BOOTLOADERS=y
diff --git a/boards/ark/can-flow/debug.cmake b/boards/ark/can-flow/debug.cmake
deleted file mode 100644
index ddcb65e86744..000000000000
--- a/boards/ark/can-flow/debug.cmake
+++ /dev/null
@@ -1,33 +0,0 @@
-include (${CMAKE_CURRENT_LIST_DIR}/uavcan_board_identity)
-
-px4_add_board(
- PLATFORM nuttx
- VENDOR ark
- MODEL can-flow
- LABEL debug
- TOOLCHAIN arm-none-eabi
- ARCHITECTURE cortex-m4
- CONSTRAINED_MEMORY
- ROMFSROOT cannode
- UAVCAN_INTERFACES 1
- DRIVERS
- bootloaders
- imu/bosch/bmi088
- optical_flow/paw3902
- uavcannode
- MODULES
- #ekf2
- load_mon
- #sensors
- SYSTEMCMDS
- mft
- mtd
- param
- perf
- reboot
- system_time
- top
- topic_listener
- ver
- work_queue
-)
diff --git a/boards/ark/can-flow/default.cmake b/boards/ark/can-flow/default.cmake
deleted file mode 100644
index 7ac68b3f10ce..000000000000
--- a/boards/ark/can-flow/default.cmake
+++ /dev/null
@@ -1,34 +0,0 @@
-include (${CMAKE_CURRENT_LIST_DIR}/uavcan_board_identity)
-
-px4_add_board(
- PLATFORM nuttx
- VENDOR ark
- MODEL can-flow
- LABEL default
- TOOLCHAIN arm-none-eabi
- ARCHITECTURE cortex-m4
- CONSTRAINED_FLASH
- CONSTRAINED_MEMORY
- ROMFSROOT cannode
- UAVCAN_INTERFACES 1
- DRIVERS
- bootloaders
- imu/bosch/bmi088
- optical_flow/paw3902
- uavcannode
- MODULES
- #ekf2
- #load_mon
- #sensors
- SYSTEMCMDS
- mft
- mtd
- param
- #perf
- #reboot
- #system_time
- #top
- #topic_listener
- #ver
- #work_queue
-)
diff --git a/boards/ark/can-flow/default.px4board b/boards/ark/can-flow/default.px4board
new file mode 100644
index 000000000000..48b3132cc3d9
--- /dev/null
+++ b/boards/ark/can-flow/default.px4board
@@ -0,0 +1,26 @@
+CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
+CONFIG_BOARD_ARCHITECTURE="cortex-m4"
+CONFIG_BOARD_ROMFSROOT="cannode"
+CONFIG_BOARD_CONSTRAINED_FLASH=y
+CONFIG_BOARD_NO_HELP=y
+CONFIG_BOARD_CONSTRAINED_MEMORY=y
+CONFIG_DRIVERS_BOOTLOADERS=y
+CONFIG_DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50=y
+CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
+CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
+CONFIG_DRIVERS_OPTICAL_FLOW_PAW3902=y
+CONFIG_BOARD_UAVCAN_INTERFACES=1
+CONFIG_DRIVERS_UAVCANNODE=y
+CONFIG_MODULES_GYRO_CALIBRATION=y
+CONFIG_MODULES_SENSORS=y
+# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set
+# CONFIG_SENSORS_VEHICLE_AIR_DATA is not set
+# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set
+# CONFIG_SENSORS_VEHICLE_MAGNETOMETER is not set
+CONFIG_SYSTEMCMDS_PARAM=y
+CONFIG_SYSTEMCMDS_PERF=y
+CONFIG_SYSTEMCMDS_TOP=y
+CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
+CONFIG_SYSTEMCMDS_UORB=y
+CONFIG_SYSTEMCMDS_VER=y
+CONFIG_SYSTEMCMDS_WORK_QUEUE=y
diff --git a/boards/ark/can-flow/init/rc.board_sensors b/boards/ark/can-flow/init/rc.board_sensors
index 7750a31898b9..b7502f98fde5 100644
--- a/boards/ark/can-flow/init/rc.board_sensors
+++ b/boards/ark/can-flow/init/rc.board_sensors
@@ -3,7 +3,15 @@
# board sensors init
#------------------------------------------------------------------------------
+param set-default IMU_GYRO_RATEMAX 1000
+
# Internal SPI
-paw3902 -s start -Y 90
-bmi088 -A -s -R 4 start
-bmi088 -G -s -R 4 start
+paw3902 -s start -Y 180
+
+if ! icm42688p -R 0 -s start
+then
+ bmi088 -A -s -R 4 start
+ bmi088 -G -s -R 4 start
+fi
+
+afbrs50 start
diff --git a/boards/ark/can-flow/nuttx-config/canbootloader/defconfig b/boards/ark/can-flow/nuttx-config/canbootloader/defconfig
index 40dffb67e84d..75230422cf17 100644
--- a/boards/ark/can-flow/nuttx-config/canbootloader/defconfig
+++ b/boards/ark/can-flow/nuttx-config/canbootloader/defconfig
@@ -7,7 +7,7 @@
#
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
-CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
+CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/can-flow/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32"
@@ -36,17 +36,10 @@ CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_LIB_BOARDCTL=y
-CONFIG_MAX_TASKS=0
+CONFIG_FS_PROCFS_MAX_TASKS=0
CONFIG_MM_REGIONS=2
CONFIG_NAME_MAX=0
CONFIG_NUNGET_CHARS=0
-CONFIG_NXFONTS_DISABLE_16BPP=y
-CONFIG_NXFONTS_DISABLE_1BPP=y
-CONFIG_NXFONTS_DISABLE_24BPP=y
-CONFIG_NXFONTS_DISABLE_2BPP=y
-CONFIG_NXFONTS_DISABLE_32BPP=y
-CONFIG_NXFONTS_DISABLE_4BPP=y
-CONFIG_NXFONTS_DISABLE_8BPP=y
CONFIG_PREALLOC_TIMERS=0
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=262144
diff --git a/boards/ark/can-flow/nuttx-config/include/board.h b/boards/ark/can-flow/nuttx-config/include/board.h
index cd6ea967dbb2..09db41dead05 100644
--- a/boards/ark/can-flow/nuttx-config/include/board.h
+++ b/boards/ark/can-flow/nuttx-config/include/board.h
@@ -124,17 +124,13 @@
#define GPIO_CAN1_RX GPIO_CAN1_RX_2
#define GPIO_CAN1_TX GPIO_CAN1_TX_2
-/* I2C */
-#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1
-#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1
-
/* SPI */
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
-#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1
-#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1
-#define GPIO_SPI2_SCK GPIO_SPI2_SCK_1
+#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */
+#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */
+#define GPIO_SPI2_SCK GPIO_SPI2_SCK_1 /* PB10 */
#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/boards/ark/can-flow/nuttx-config/include/board_dma_map.h b/boards/ark/can-flow/nuttx-config/include/board_dma_map.h
index 2d52cfbfec2a..0eb81fc589d6 100644
--- a/boards/ark/can-flow/nuttx-config/include/board_dma_map.h
+++ b/boards/ark/can-flow/nuttx-config/include/board_dma_map.h
@@ -35,11 +35,10 @@
// DMA1 Channel/Stream Selections
//--------------------------------------------//---------------------------//----------------
-
+#define DMACHAN_SPI2_RX DMAMAP_SPI2_RX // DMA1, Stream 3, Channel 0
+#define DMACHAN_SPI2_TX DMAMAP_SPI2_TX // DMA1, Stream 4, Channel 0
// DMA2 Channel/Stream Selections
//--------------------------------------------//---------------------------//----------------
#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_2 // DMA2, Stream 2, Channel 3
-#define DMACHAN_SPI2_RX DMAMAP_SPI2_RX // DMA2, Stream 3, Channel 0
-#define DMACHAN_SPI2_TX DMAMAP_SPI2_TX // DMA2, Stream 4, Channel 0
-#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 5, Channel 3
+#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2 // DMA2, Stream 5, Channel 3
diff --git a/boards/ark/can-flow/nuttx-config/nsh/defconfig b/boards/ark/can-flow/nuttx-config/nsh/defconfig
index de632fc595ff..7c8691089f10 100644
--- a/boards/ark/can-flow/nuttx-config/nsh/defconfig
+++ b/boards/ark/can-flow/nuttx-config/nsh/defconfig
@@ -15,12 +15,13 @@
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
+# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_TIME is not set
# CONFIG_STM32_DMACAPABLE is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
-CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
+CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/can-flow/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32"
@@ -56,8 +57,6 @@ CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
-CONFIG_I2C=y
-CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
@@ -70,18 +69,13 @@ CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
-CONFIG_NFILE_DESCRIPTORS=12
CONFIG_NSH_ARCHINIT=y
-CONFIG_NSH_ARCHROMFS=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_IFCONFIG=y
CONFIG_NSH_DISABLE_IFUPDOWN=y
-CONFIG_NSH_DISABLE_MB=y
-CONFIG_NSH_DISABLE_MH=y
-CONFIG_NSH_DISABLE_MW=y
CONFIG_NSH_DISABLE_TELNETD=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
@@ -97,23 +91,21 @@ CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_SETSPEED=y
-CONFIG_RAMTRON_WRITEWAIT=y
CONFIG_RAM_SIZE=262144
CONFIG_RAM_START=0x20000000
CONFIG_RAW_BINARY=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
-CONFIG_SCHED_HPWORKPRIORITY=249
-CONFIG_SCHED_HPWORKSTACKSIZE=1280
+CONFIG_SCHED_HPWORKPRIORITY=254
+CONFIG_SCHED_HPWORKSTACKSIZE=3000
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
-CONFIG_SEM_NNESTPRIO=8
-CONFIG_SEM_PREALLOCHOLDERS=0
+CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@@ -130,7 +122,6 @@ CONFIG_STM32_DMA1=y
CONFIG_STM32_DMA2=y
CONFIG_STM32_FLASH_PREFETCH=y
CONFIG_STM32_FLOWCONTROL_BROKEN=y
-CONFIG_STM32_I2C1=y
CONFIG_STM32_JTAG_SW_ENABLE=y
CONFIG_STM32_PWR=y
CONFIG_STM32_RTC=y
@@ -142,10 +133,10 @@ CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32_SPI1=y
CONFIG_STM32_SPI1_DMA=y
-CONFIG_STM32_SPI1_DMA_BUFFER=1024
+CONFIG_STM32_SPI1_DMA_BUFFER=2048
CONFIG_STM32_SPI2=y
CONFIG_STM32_SPI2_DMA=y
-CONFIG_STM32_SPI2_DMA_BUFFER=1024
+CONFIG_STM32_SPI2_DMA_BUFFER=2048
CONFIG_STM32_SPI_DMA=y
CONFIG_STM32_TIM8=y
CONFIG_STM32_USART2=y
diff --git a/boards/ark/can-flow/src/CMakeLists.txt b/boards/ark/can-flow/src/CMakeLists.txt
index 0a0d16082306..4fae41fc0ecb 100644
--- a/boards/ark/can-flow/src/CMakeLists.txt
+++ b/boards/ark/can-flow/src/CMakeLists.txt
@@ -49,7 +49,6 @@ if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader")
else()
add_library(drivers_board
can.c
- i2c.cpp
init.c
led.c
spi.cpp
@@ -62,6 +61,5 @@ else()
nuttx_arch
nuttx_drivers
px4_layer
- arch_io_pins
)
endif()
diff --git a/boards/ark/can-flow/src/board_config.h b/boards/ark/can-flow/src/board_config.h
index 44424aeae78f..40f302e19b79 100644
--- a/boards/ark/can-flow/src/board_config.h
+++ b/boards/ark/can-flow/src/board_config.h
@@ -48,6 +48,7 @@
/* CAN termination software control */
#define GPIO_CAN1_TERMINATION /* PB13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
+#define GPIO_CAN_TERM GPIO_CAN1_TERMINATION
/* Boot config */
#define GPIO_BOOT_CONFIG /* PC15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN15|GPIO_EXTI)
@@ -56,6 +57,13 @@
#define GPIO_nLED_RED /* PB3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN3)
#define GPIO_nLED_BLUE /* PA8 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN8)
+#define BROADCOM_AFBR_S50_S2PI_SPI_BUS 2
+#define BROADCOM_AFBR_S50_S2PI_CS /* PB12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN12)
+#define BROADCOM_AFBR_S50_S2PI_IRQ /* PB4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN4|GPIO_EXTI)
+#define BROADCOM_AFBR_S50_S2PI_CLK /* PB10 */ GPIO_SPI2_SCK_1
+#define BROADCOM_AFBR_S50_S2PI_MOSI /* PB15 */ GPIO_SPI2_MOSI_1
+#define BROADCOM_AFBR_S50_S2PI_MISO /* PB14 */ GPIO_SPI2_MISO_1
+
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
#define BOARD_OVERLOAD_LED LED_RED
#define BOARD_ARMED_STATE_LED LED_BLUE
diff --git a/boards/ark/can-flow/src/init.c b/boards/ark/can-flow/src/init.c
index 501c13d29d73..8b1662d2d28c 100644
--- a/boards/ark/can-flow/src/init.c
+++ b/boards/ark/can-flow/src/init.c
@@ -49,6 +49,7 @@
#include
#include
#include
+#include
#include
@@ -60,6 +61,7 @@
#include
#include
+#include
#include
@@ -87,6 +89,8 @@ __END_DECLS
__EXPORT void stm32_boardinitialize(void)
{
+ watchdog_init();
+
// Configure CAN interface
stm32_configgpio(GPIO_CAN1_RX);
stm32_configgpio(GPIO_CAN1_TX);
@@ -142,7 +146,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
if (result != OK) {
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
- return -ENODEV;
}
#endif // FLASH_BASED_PARAMS
diff --git a/boards/ark/can-flow/src/spi.cpp b/boards/ark/can-flow/src/spi.cpp
index d517d36c28ac..92d24684a885 100644
--- a/boards/ark/can-flow/src/spi.cpp
+++ b/boards/ark/can-flow/src/spi.cpp
@@ -39,6 +39,7 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortA, GPIO::Pin4}, SPI::DRDY{GPIO::PortB, GPIO::Pin0}),
+ initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortA, GPIO::Pin4}, SPI::DRDY{GPIO::PortB, GPIO::Pin0}),
initSPIDevice(DRV_FLOW_DEVTYPE_PAW3902, SPI::CS{GPIO::PortB, GPIO::Pin5}, SPI::DRDY{GPIO::PortB, GPIO::Pin2}),
}),
initSPIBus(SPI::Bus::SPI2, {
diff --git a/boards/ark/can-gps/canbootloader.px4board b/boards/ark/can-gps/canbootloader.px4board
new file mode 100644
index 000000000000..46917280f6a4
--- /dev/null
+++ b/boards/ark/can-gps/canbootloader.px4board
@@ -0,0 +1,5 @@
+CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
+CONFIG_BOARD_ARCHITECTURE="cortex-m4"
+CONFIG_BOARD_ROMFSROOT=""
+CONFIG_BOARD_CONSTRAINED_MEMORY=y
+CONFIG_DRIVERS_BOOTLOADERS=y
diff --git a/boards/ark/can-gps/default.px4board b/boards/ark/can-gps/default.px4board
new file mode 100644
index 000000000000..8f69c01983e1
--- /dev/null
+++ b/boards/ark/can-gps/default.px4board
@@ -0,0 +1,30 @@
+CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
+CONFIG_BOARD_ARCHITECTURE="cortex-m4"
+CONFIG_BOARD_ROMFSROOT="cannode"
+CONFIG_BOARD_CONSTRAINED_FLASH=y
+CONFIG_BOARD_NO_HELP=y
+CONFIG_BOARD_CONSTRAINED_MEMORY=y
+CONFIG_DRIVERS_BAROMETER_BMP388=y
+CONFIG_DRIVERS_BOOTLOADERS=y
+CONFIG_DRIVERS_GPS=y
+CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
+CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y
+CONFIG_DRIVERS_SAFETY_BUTTON=y
+CONFIG_DRIVERS_TONE_ALARM=y
+CONFIG_BOARD_UAVCAN_INTERFACES=1
+CONFIG_DRIVERS_UAVCANNODE=y
+CONFIG_MODULES_GYRO_CALIBRATION=y
+CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
+CONFIG_MODULES_SENSORS=y
+# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set
+# CONFIG_SENSORS_VEHICLE_AIR_DATA is not set
+# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set
+CONFIG_SYSTEMCMDS_PARAM=y
+CONFIG_SYSTEMCMDS_PERF=y
+CONFIG_SYSTEMCMDS_REBOOT=y
+CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
+CONFIG_SYSTEMCMDS_TOP=y
+CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
+CONFIG_SYSTEMCMDS_UORB=y
+CONFIG_SYSTEMCMDS_VER=y
+CONFIG_SYSTEMCMDS_WORK_QUEUE=y
diff --git a/boards/ark/can-gps/firmware.prototype b/boards/ark/can-gps/firmware.prototype
new file mode 100644
index 000000000000..d7b32b3bd539
--- /dev/null
+++ b/boards/ark/can-gps/firmware.prototype
@@ -0,0 +1,13 @@
+{
+ "board_id": 81,
+ "magic": "PX4FWv1",
+ "description": "Firmware for the ARK gps board",
+ "image": "",
+ "build_time": 0,
+ "summary": "ARKGPS",
+ "version": "0.1",
+ "image_size": 0,
+ "image_maxsize": 2080768,
+ "git_identity": "",
+ "board_revision": 0
+}
diff --git a/boards/ark/can-gps/init/rc.board_defaults b/boards/ark/can-gps/init/rc.board_defaults
new file mode 100644
index 000000000000..480d2c92c58d
--- /dev/null
+++ b/boards/ark/can-gps/init/rc.board_defaults
@@ -0,0 +1,10 @@
+#!/bin/sh
+#
+# board specific defaults
+#------------------------------------------------------------------------------
+
+param set-default CBRK_IO_SAFETY 0
+param set-default MBE_ENABLE 1
+
+safety_button start
+tone_alarm start
diff --git a/boards/ark/can-gps/init/rc.board_sensors b/boards/ark/can-gps/init/rc.board_sensors
new file mode 100644
index 000000000000..d74d5f74b24d
--- /dev/null
+++ b/boards/ark/can-gps/init/rc.board_sensors
@@ -0,0 +1,11 @@
+#!/bin/sh
+#
+# board sensors init
+#------------------------------------------------------------------------------
+gps start -d /dev/ttyS0 -p ubx
+
+icm42688p -R 0 -s start
+
+bmp388 -I -b 2 start
+
+bmm150 -I -b 1 start
diff --git a/boards/ark/can-gps/nuttx-config/canbootloader/defconfig b/boards/ark/can-gps/nuttx-config/canbootloader/defconfig
new file mode 100644
index 000000000000..8d495caa8dae
--- /dev/null
+++ b/boards/ark/can-gps/nuttx-config/canbootloader/defconfig
@@ -0,0 +1,61 @@
+#
+# This file is autogenerated: PLEASE DO NOT EDIT IT.
+#
+# You can use "make menuconfig" to make any modifications to the installed .config file.
+# You can then do "make savedefconfig" to generate a new defconfig file that includes your
+# modifications.
+#
+CONFIG_ARCH="arm"
+CONFIG_ARCH_BOARD_CUSTOM=y
+CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/can-gps/nuttx-config"
+CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
+CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARCH_CHIP_STM32=y
+CONFIG_ARCH_CHIP_STM32F412CE=y
+CONFIG_ARCH_INTERRUPTSTACK=4096
+CONFIG_ARMV7M_MEMCPY=y
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_BINFMT_DISABLE=y
+CONFIG_BOARD_LOOPSPERMSEC=16717
+CONFIG_C99_BOOL8=y
+CONFIG_CLOCK_MONOTONIC=y
+CONFIG_DEBUG_FULLOPT=y
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEFAULT_SMALL=y
+CONFIG_DISABLE_MOUNTPOINT=y
+CONFIG_DISABLE_MQUEUE=y
+CONFIG_DISABLE_PTHREAD=y
+CONFIG_EXPERIMENTAL=y
+CONFIG_FDCLONE_DISABLE=y
+CONFIG_FDCLONE_STDIO=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+CONFIG_IDLETHREAD_STACKSIZE=4096
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_LIBC_LONG_LONG=y
+CONFIG_LIBC_STRERROR=y
+CONFIG_LIB_BOARDCTL=y
+CONFIG_FS_PROCFS_MAX_TASKS=0
+CONFIG_MM_REGIONS=2
+CONFIG_NAME_MAX=0
+CONFIG_NUNGET_CHARS=0
+CONFIG_PREALLOC_TIMERS=0
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_RAM_SIZE=262144
+CONFIG_RAM_START=0x20010000
+CONFIG_RAW_BINARY=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_SIG_DEFAULT=y
+CONFIG_SIG_SIGALRM_ACTION=y
+CONFIG_SIG_SIGUSR1_ACTION=y
+CONFIG_SIG_SIGUSR2_ACTION=y
+CONFIG_STACK_COLORATION=y
+CONFIG_START_DAY=30
+CONFIG_START_MONTH=11
+CONFIG_STDIO_DISABLE_BUFFERING=y
+CONFIG_STM32_NOEXT_VECTORS=y
+CONFIG_STM32_TIM8=y
+CONFIG_TASK_NAME_SIZE=0
+CONFIG_USEC_PER_TICK=1000
+CONFIG_USERMAIN_STACKSIZE=4096
diff --git a/boards/ark/can-gps/nuttx-config/include/board.h b/boards/ark/can-gps/nuttx-config/include/board.h
new file mode 100644
index 000000000000..526392b92bbd
--- /dev/null
+++ b/boards/ark/can-gps/nuttx-config/include/board.h
@@ -0,0 +1,152 @@
+/************************************************************************************
+ * configs/px4fmu/include/board.h
+ * include/arch/board/board.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * 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 NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+#include "board_dma_map.h"
+
+#ifndef __ARCH_BOARD_BOARD_H
+#define __ARCH_BOARD_BOARD_H
+
+#include
+#ifndef __ASSEMBLY__
+# include
+#endif
+
+#include
+
+/* HSI - 8 MHz RC factory-trimmed
+ * LSI - 32 KHz RC
+ * HSE - 8 MHz Crystal
+ * LSE - not installed
+ */
+#define STM32_BOARD_USEHSE 1
+#define STM32_BOARD_XTAL 8000000
+#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
+
+#define STM32_HSI_FREQUENCY 16000000ul
+#define STM32_LSI_FREQUENCY 32000
+
+/* Main PLL Configuration */
+#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8)
+#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(384)
+#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_4
+#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(8)
+#define STM32_PLLCFG_PLLR RCC_PLLCFG_PLLR(2)
+
+#define STM32_RCC_PLLI2SCFGR_PLLI2SM RCC_PLLI2SCFGR_PLLI2SM(16)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SSRC RCC_PLLI2SCFGR_PLLI2SSRC(0) /* HSE or HSI depending on PLLSRC of PLLCFGR*/
+
+#define STM32_RCC_DCKCFGR2_CK48MSEL RCC_DCKCFGR2_CK48MSEL_PLL
+#define STM32_RCC_DCKCFGR2_FMPI2C1SEL RCC_DCKCFGR2_FMPI2C1SEL_APB
+#define STM32_RCC_DCKCFGR2_SDIOSEL RCC_DCKCFGR2_SDIOSEL_48MHZ
+
+#define STM32_SYSCLK_FREQUENCY 96000000ul
+
+/* AHB clock (HCLK) is SYSCLK (96MHz) */
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
+#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* Same as above, to satisfy compiler */
+
+/* APB1 clock (PCLK1) is HCLK/2 (48MHz) */
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
+
+/* Timers driven from APB1 will be twice PCLK1 (see page 112 of reference manual) */
+#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
+
+/* APB2 clock (PCLK2) is HCLK (96MHz) */
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK */
+#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY)
+
+/* Timers driven from APB2 will be PCLK2 since no prescale division */
+#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM9_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM10_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM11_CLKIN (STM32_PCLK2_FREQUENCY)
+
+/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx otherwise frequency is 2xAPBx. */
+#define BOARD_TIM2_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM3_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM4_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM5_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM6_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM7_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM8_FREQUENCY (2 * STM32_PCLK2_FREQUENCY)
+
+/* Alternate function pin selections ************************************************/
+
+/* UARTs */
+#define GPIO_USART1_RX GPIO_USART1_RX_2
+#define GPIO_USART1_TX GPIO_USART1_TX_3
+
+#define GPIO_USART2_RX GPIO_USART2_RX_1
+#define GPIO_USART2_TX GPIO_USART2_TX_1
+
+/* CAN */
+#define GPIO_CAN1_RX GPIO_CAN1_RX_1
+#define GPIO_CAN1_TX GPIO_CAN1_TX_1
+
+/* I2C */
+
+#define GPIO_MCU_I2C1_SCL
+#define GPIO_MCU_I2C1_SDA
+
+#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1
+#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1
+
+#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6)
+#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7)
+
+#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
+#define GPIO_I2C2_SDA GPIO_I2C2_SDA_4
+
+#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9)
+#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10)
+
+/* SPI */
+#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
+#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
+#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
+
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/boards/ark/can-gps/nuttx-config/include/board_dma_map.h b/boards/ark/can-gps/nuttx-config/include/board_dma_map.h
new file mode 100644
index 000000000000..f6e577b3d5fe
--- /dev/null
+++ b/boards/ark/can-gps/nuttx-config/include/board_dma_map.h
@@ -0,0 +1,43 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+// DMA1 Channel/Stream Selections
+//--------------------------------------------//---------------------------//----------------
+
+
+// DMA2 Channel/Stream Selections
+//--------------------------------------------//---------------------------//----------------
+#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_2 // DMA2, Stream 2, Channel 3
+#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 5, Channel 3
diff --git a/boards/ark/can-gps/nuttx-config/nsh/defconfig b/boards/ark/can-gps/nuttx-config/nsh/defconfig
new file mode 100644
index 000000000000..c305c085f48b
--- /dev/null
+++ b/boards/ark/can-gps/nuttx-config/nsh/defconfig
@@ -0,0 +1,158 @@
+#
+# This file is autogenerated: PLEASE DO NOT EDIT IT.
+#
+# You can use "make menuconfig" to make any modifications to the installed .config file.
+# You can then do "make savedefconfig" to generate a new defconfig file that includes your
+# modifications.
+#
+# CONFIG_DISABLE_OS_API is not set
+# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
+# CONFIG_NSH_DISABLEBG is not set
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLE_DF is not set
+# CONFIG_NSH_DISABLE_EXEC is not set
+# CONFIG_NSH_DISABLE_EXIT is not set
+# CONFIG_NSH_DISABLE_GET is not set
+# CONFIG_NSH_DISABLE_ITEF is not set
+# CONFIG_NSH_DISABLE_LOOPS is not set
+# CONFIG_NSH_DISABLE_MKFATFS is not set
+# CONFIG_NSH_DISABLE_SEMICOLON is not set
+# CONFIG_NSH_DISABLE_TIME is not set
+# CONFIG_STM32_DMACAPABLE is not set
+CONFIG_ARCH="arm"
+CONFIG_ARCH_BOARD_CUSTOM=y
+CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/can-gps/nuttx-config"
+CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
+CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARCH_CHIP_STM32=y
+CONFIG_ARCH_CHIP_STM32F412CE=y
+CONFIG_ARCH_INTERRUPTSTACK=512
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_ARMV7M_MEMCPY=y
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_BOARDCTL_RESET=y
+CONFIG_BOARD_LOOPSPERMSEC=16717
+CONFIG_BOARD_RESET_ON_ASSERT=2
+CONFIG_BUILTIN=y
+CONFIG_C99_BOOL8=y
+CONFIG_CLOCK_MONOTONIC=y
+CONFIG_DEBUG_FULLOPT=y
+CONFIG_DEBUG_HARDFAULT_ALERT=y
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEFAULT_SMALL=y
+CONFIG_DEV_FIFO_SIZE=0
+CONFIG_DEV_PIPE_MAXSIZE=1024
+CONFIG_DEV_PIPE_SIZE=70
+CONFIG_FDCLONE_STDIO=y
+CONFIG_FS_BINFS=y
+CONFIG_FS_CROMFS=y
+CONFIG_FS_FAT=y
+CONFIG_FS_FATTIME=y
+CONFIG_FS_PROCFS=y
+CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
+CONFIG_FS_PROCFS_REGISTER=y
+CONFIG_FS_ROMFS=y
+CONFIG_GRAN=y
+CONFIG_GRAN_INTR=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+CONFIG_I2C=y
+CONFIG_I2C_RESET=y
+CONFIG_IDLETHREAD_STACKSIZE=750
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_LIBC_LONG_LONG=y
+CONFIG_LIBC_STRERROR=y
+CONFIG_MEMSET_64BIT=y
+CONFIG_MEMSET_OPTSPEED=y
+CONFIG_MM_REGIONS=2
+CONFIG_MTD=y
+CONFIG_MTD_BYTE_WRITE=y
+CONFIG_MTD_PARTITION=y
+CONFIG_MTD_RAMTRON=y
+CONFIG_NAME_MAX=40
+CONFIG_NSH_ARCHINIT=y
+CONFIG_NSH_ARGCAT=y
+CONFIG_NSH_BUILTIN_APPS=y
+CONFIG_NSH_CMDPARMS=y
+CONFIG_NSH_CROMFSETC=y
+CONFIG_NSH_DISABLE_IFCONFIG=y
+CONFIG_NSH_DISABLE_IFUPDOWN=y
+CONFIG_NSH_DISABLE_TELNETD=y
+CONFIG_NSH_LINELEN=128
+CONFIG_NSH_MAXARGUMENTS=15
+CONFIG_NSH_NESTDEPTH=8
+CONFIG_NSH_QUOTE=y
+CONFIG_NSH_ROMFSETC=y
+CONFIG_NSH_ROMFSSECTSIZE=128
+CONFIG_NSH_STRERROR=y
+CONFIG_NSH_VARS=y
+CONFIG_PIPES=y
+CONFIG_PREALLOC_TIMERS=50
+CONFIG_PRIORITY_INHERITANCE=y
+CONFIG_PTHREAD_MUTEX_ROBUST=y
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_RAMTRON_SETSPEED=y
+CONFIG_RAM_SIZE=262144
+CONFIG_RAM_START=0x20000000
+CONFIG_RAW_BINARY=y
+CONFIG_RTC_DATETIME=y
+CONFIG_SCHED_ATEXIT=y
+CONFIG_SCHED_HPWORK=y
+CONFIG_SCHED_HPWORKPRIORITY=249
+CONFIG_SCHED_HPWORKSTACKSIZE=1280
+CONFIG_SCHED_INSTRUMENTATION=y
+CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
+CONFIG_SCHED_LPWORK=y
+CONFIG_SCHED_LPWORKPRIORITY=50
+CONFIG_SCHED_LPWORKSTACKSIZE=1632
+CONFIG_SCHED_WAITPID=y
+CONFIG_SEM_PREALLOCHOLDERS=32
+CONFIG_SERIAL_TERMIOS=y
+CONFIG_SIG_DEFAULT=y
+CONFIG_SIG_SIGALRM_ACTION=y
+CONFIG_SIG_SIGUSR1_ACTION=y
+CONFIG_SIG_SIGUSR2_ACTION=y
+CONFIG_SIG_SIGWORK=4
+CONFIG_STACK_COLORATION=y
+CONFIG_START_DAY=30
+CONFIG_START_MONTH=11
+CONFIG_STDIO_BUFFER_SIZE=32
+CONFIG_STM32_ADC1=y
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=y
+CONFIG_STM32_FLASH_PREFETCH=y
+CONFIG_STM32_FLOWCONTROL_BROKEN=y
+CONFIG_STM32_I2C1=y
+CONFIG_STM32_I2C2=y
+CONFIG_STM32_JTAG_SW_ENABLE=y
+CONFIG_STM32_PWR=y
+CONFIG_STM32_RTC=y
+CONFIG_STM32_RTC_HSECLOCK=y
+CONFIG_STM32_RTC_MAGIC=0xfacefeee
+CONFIG_STM32_RTC_MAGIC_REG=1
+CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef
+CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
+CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
+CONFIG_STM32_SPI1=y
+CONFIG_STM32_SPI1_DMA=y
+CONFIG_STM32_SPI1_DMA_BUFFER=1024
+CONFIG_STM32_SPI_DMA=y
+CONFIG_STM32_TIM8=y
+CONFIG_STM32_USART1=y
+CONFIG_STM32_USART2=y
+CONFIG_STM32_USART_BREAKS=y
+CONFIG_STM32_WWDG=y
+CONFIG_SYSTEM_NSH=y
+CONFIG_TASK_NAME_SIZE=24
+CONFIG_USART1_BAUD=57600
+CONFIG_USART1_RXBUFSIZE=600
+CONFIG_USART1_TXBUFSIZE=1100
+CONFIG_USART2_BAUD=57600
+CONFIG_USART2_RXBUFSIZE=600
+CONFIG_USART2_SERIAL_CONSOLE=y
+CONFIG_USART2_TXBUFSIZE=1100
+CONFIG_USEC_PER_TICK=1000
+CONFIG_USERMAIN_STACKSIZE=2624
+CONFIG_USER_ENTRYPOINT="nsh_main"
diff --git a/boards/ark/can-gps/nuttx-config/scripts/canbootloader_script.ld b/boards/ark/can-gps/nuttx-config/scripts/canbootloader_script.ld
new file mode 100644
index 000000000000..cbf9fddc32dc
--- /dev/null
+++ b/boards/ark/can-gps/nuttx-config/scripts/canbootloader_script.ld
@@ -0,0 +1,134 @@
+/****************************************************************************
+ * nuttx-config/scripts/canbootloader_script.ld
+ *
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
+ * 256Kb of SRAM. SRAM is split up into three blocks:
+ *
+ * 1) 112Kb of SRAM beginning at address 0x2000:0000
+ * 2) 16Kb of SRAM beginning at address 0x2001:c000
+ * 3) 64Kb of SRAM beginning at address 0x2002:0000
+ * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000
+ *
+ * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
+ * where the code expects to begin execution by jumping to the entry point in
+ * the 0x0800:0000 address range.
+ *
+ * The first 0x10000 of flash is reserved for the bootloader.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08000000, LENGTH = 32K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
+}
+
+OUTPUT_ARCH(arm)
+
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/boards/ark/can-gps/nuttx-config/scripts/script.ld b/boards/ark/can-gps/nuttx-config/scripts/script.ld
new file mode 100644
index 000000000000..c63c74994199
--- /dev/null
+++ b/boards/ark/can-gps/nuttx-config/scripts/script.ld
@@ -0,0 +1,146 @@
+/****************************************************************************
+ * scripts/ld.script
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
+ * 256Kb of SRAM. SRAM is split up into three blocks:
+ *
+ * 1) 112Kb of SRAM beginning at address 0x2000:0000
+ * 2) 16Kb of SRAM beginning at address 0x2001:c000
+ * 3) 64Kb of SRAM beginning at address 0x2002:0000
+ * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000
+ *
+ * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
+ * where the code expects to begin execution by jumping to the entry point in
+ * the 0x0800:0000 address range.
+ *
+ * The first 0x10000 of flash is reserved for the bootloader.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08010000, LENGTH = 448K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
+}
+
+OUTPUT_ARCH(arm)
+
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+EXTERN(_bootdelay_signature)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ . = ALIGN(8);
+ /*
+ * This section positions the app_descriptor_t used
+ * by the make_can_boot_descriptor.py tool to set
+ * the application image's descriptor so that the
+ * uavcan bootloader has the ability to validate the
+ * image crc, size etc
+ */
+ KEEP(*(.app_descriptor))
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/boards/ark/can-gps/src/CMakeLists.txt b/boards/ark/can-gps/src/CMakeLists.txt
new file mode 100644
index 000000000000..06bd98156f22
--- /dev/null
+++ b/boards/ark/can-gps/src/CMakeLists.txt
@@ -0,0 +1,67 @@
+############################################################################
+#
+# Copyright (c) 2020 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader")
+
+ add_library(drivers_board
+ boot_config.h
+ boot.c
+ led.c
+ led.h
+ )
+ target_link_libraries(drivers_board
+ PRIVATE
+ nuttx_arch
+ nuttx_drivers
+ canbootloader
+ )
+ target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/canbootloader)
+
+else()
+ add_library(drivers_board
+ can.c
+ i2c.cpp
+ init.c
+ led.c
+ spi.cpp
+ )
+
+ target_link_libraries(drivers_board
+ PRIVATE
+ arch_spi
+ drivers__led # drv_led_start
+ nuttx_arch
+ nuttx_drivers
+ px4_layer
+ )
+endif()
diff --git a/boards/ark/can-gps/src/board_config.h b/boards/ark/can-gps/src/board_config.h
new file mode 100644
index 000000000000..723310472f4a
--- /dev/null
+++ b/boards/ark/can-gps/src/board_config.h
@@ -0,0 +1,122 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file board_config.h
+ *
+ * board internal definitions
+ */
+
+#pragma once
+
+#include
+#include
+#include
+
+/* BUTTON */
+#define GPIO_BTN_SAFETY /* PB15 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN15)
+
+/* Safety LED */
+#define GPIO_LED_SAFETY /* PA1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN1)
+
+/* Tone alarm output. */
+#define TONE_ALARM_TIMER 2 /* timer 2 */
+#define TONE_ALARM_CHANNEL 1 /* channel 1 */
+#define GPIO_TONE_ALARM_IDLE /* PA0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_TONE_ALARM /* PA0 */ (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
+
+/* CAN Silent mode control */
+#define GPIO_CAN1_SILENT_S0 /* PB12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12)
+
+/* CAN termination software control */
+#define GPIO_CAN1_TERMINATION /* PB13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
+#define GPIO_CAN_TERM GPIO_CAN1_TERMINATION
+
+/* ICM42688p FSYNC */
+#define GPIO_42688P_FSYNC /* PB8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
+
+/* Boot config */
+#define GPIO_BOOT_CONFIG /* PC15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN15|GPIO_EXTI)
+
+/* LEDs are driven with open drain to support Anode to 5V or 3.3V */
+#define GPIO_TIM1_CH1 /* PA8 */ (GPIO_TIM1_CH1_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
+#define GPIO_TIM1_CH2 /* PA9 */ (GPIO_TIM1_CH2_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
+#define GPIO_TIM1_CH3 /* PA10 */ (GPIO_TIM1_CH3_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
+
+#define GPIO_I2C1_SCL_RESET /* PB6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN6)
+#define GPIO_I2C1_SDA_RESET /* PB7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN7)
+
+#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
+
+#define GPIO_USART1_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3)
+#define GPIO_USART1_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15)
+
+#define GPIO_USART2_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_USART2_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN2)
+
+#define FLASH_BASED_PARAMS
+
+/* High-resolution timer */
+#define HRT_TIMER 3 /* use timer 3 for the HRT */
+#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */
+
+#define PX4_GPIO_INIT_LIST { \
+ GPIO_BTN_SAFETY, \
+ GPIO_LED_SAFETY, \
+ GPIO_I2C1_SCL_RESET, \
+ GPIO_I2C1_SDA_RESET, \
+ GPIO_I2C2_SCL_RESET, \
+ GPIO_I2C2_SDA_RESET, \
+ GPIO_42688P_FSYNC, \
+ GPIO_BOOT_CONFIG, \
+ GPIO_CAN1_TX, \
+ GPIO_CAN1_RX, \
+ GPIO_CAN1_SILENT_S0, \
+ GPIO_CAN1_TERMINATION, \
+ }
+
+__BEGIN_DECLS
+
+#define BOARD_HAS_N_S_RGB_LED 1
+#define BOARD_MAX_LEDS BOARD_HAS_N_S_RGB_LED
+
+#ifndef __ASSEMBLY__
+
+extern void stm32_spiinitialize(void);
+
+#include
+
+#endif /* __ASSEMBLY__ */
+
+__END_DECLS
diff --git a/boards/ark/can-gps/src/boot.c b/boards/ark/can-gps/src/boot.c
new file mode 100644
index 000000000000..a26034e254f6
--- /dev/null
+++ b/boards/ark/can-gps/src/boot.c
@@ -0,0 +1,188 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 PX4 Development Team. All rights reserved.
+ * Author: Ben Dyer
+ * Pavel Kirienko
+ * David Sidrane
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include
+#include
+#include "boot_config.h"
+#include "board.h"
+
+#include
+#include
+#include
+
+#include
+#include "led.h"
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the initialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_boardinitialize(void)
+{
+ putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR);
+ stm32_configgpio(GPIO_CAN1_RX);
+ stm32_configgpio(GPIO_CAN1_TX);
+ stm32_configgpio(GPIO_CAN1_SILENT_S0);
+ stm32_configgpio(GPIO_CAN1_TERMINATION);
+ putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
+ putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
+
+#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
+ stm32_configgpio(GPIO_GETNODEINFO_JUMPER);
+#endif
+
+}
+
+/************************************************************************************
+ * Name: board_deinitialize
+ *
+ * Description:
+ * This function is called by the bootloader code prior to booting
+ * the application. Is should place the HW into an benign initialized state.
+ *
+ ************************************************************************************/
+
+void board_deinitialize(void)
+{
+ putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
+}
+
+/****************************************************************************
+ * Name: board_get_product_name
+ *
+ * Description:
+ * Called to retrieve the product name. The returned value is a assumed
+ * to be written to a pascal style string that will be length prefixed
+ * and not null terminated
+ *
+ * Input Parameters:
+ * product_name - A pointer to a buffer to write the name.
+ * maxlen - The maximum number of charter that can be written
+ *
+ * Returned Value:
+ * The length of characters written to the buffer.
+ *
+ ****************************************************************************/
+
+uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen)
+{
+ DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME));
+ memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME));
+ return UAVCAN_STRLEN(HW_UAVCAN_NAME);
+}
+
+/****************************************************************************
+ * Name: board_get_hardware_version
+ *
+ * Description:
+ * Called to retrieve the hardware version information. The function
+ * will first initialize the the callers struct to all zeros.
+ *
+ * Input Parameters:
+ * hw_version - A pointer to a uavcan_hardwareversion_t.
+ *
+ * Returned Value:
+ * Length of the unique_id
+ *
+ ****************************************************************************/
+
+size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version)
+{
+ memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t));
+
+ hw_version->major = HW_VERSION_MAJOR;
+ hw_version->minor = HW_VERSION_MINOR;
+
+ return board_get_mfguid(*(mfguid_t *) hw_version->unique_id);
+}
+
+/****************************************************************************
+ * Name: board_indicate
+ *
+ * Description:
+ * Provides User feedback to indicate the state of the bootloader
+ * on board specific hardware.
+ *
+ * Input Parameters:
+ * indication - A member of the uiindication_t
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)}
+
+typedef begin_packed_struct struct led_t {
+ uint8_t red;
+ uint8_t green;
+ uint8_t blue;
+ uint8_t hz;
+} end_packed_struct led_t;
+
+static const led_t i2l[] = {
+
+ led(0, off, 0, 0, 0, 0),
+ led(1, reset, 128, 128, 128, 30),
+ led(2, autobaud_start, 0, 128, 0, 1),
+ led(3, autobaud_end, 0, 128, 0, 2),
+ led(4, allocation_start, 0, 0, 64, 2),
+ led(5, allocation_end, 0, 128, 64, 3),
+ led(6, fw_update_start, 32, 128, 64, 3),
+ led(7, fw_update_erase_fail, 32, 128, 32, 3),
+ led(8, fw_update_invalid_response, 64, 0, 0, 1),
+ led(9, fw_update_timeout, 64, 0, 0, 2),
+ led(a, fw_update_invalid_crc, 64, 0, 0, 4),
+ led(b, jump_to_app, 0, 128, 0, 10),
+
+};
+
+void board_indicate(uiindication_t indication)
+{
+ rgb_led(i2l[indication].red,
+ i2l[indication].green,
+ i2l[indication].blue,
+ i2l[indication].hz);
+}
diff --git a/boards/ark/can-gps/src/boot_config.h b/boards/ark/can-gps/src/boot_config.h
new file mode 100644
index 000000000000..eab3c76c6c13
--- /dev/null
+++ b/boards/ark/can-gps/src/boot_config.h
@@ -0,0 +1,130 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 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 boot_config.h
+ *
+ * bootloader definitions that configures the behavior and options
+ * of the Boot loader
+ * This file is relies on the parent folder's boot_config.h file and defines
+ * different usages of the hardware for bootloading
+ */
+
+#pragma once
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+/* Bring in the board_config.h definitions
+ * todo:make this be pulled in from a targed's build
+ * files in nuttx*/
+
+#include "board_config.h"
+#include "uavcan.h"
+#include
+
+#include
+
+#include
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
+
+//todo:wrap OPT_x in in ifdefs for command line definitions
+#define OPT_TBOOT_MS 5000
+#define OPT_NODE_STATUS_RATE_MS 800
+#define OPT_NODE_INFO_RATE_MS 50
+#define OPT_BL_NUMBER_TIMERS 7
+
+/*
+ * This Option set is set to 1 ensure a provider of firmware has an
+ * opportunity update the node's firmware.
+ * This Option is the default policy and can be overridden by
+ * a jumper
+ * When this Policy is set, the node will ignore tboot and
+ * wait indefinitely for a GetNodeInfo request before booting.
+ *
+ * OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow
+ * the polarity of the jumper to be True Active
+ *
+ * wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
+ * Jumper
+ * yes 1 0 x
+ * yes 1 1 Active
+ * no 1 1 Not Active
+ * no 0 0 X
+ * yes 0 1 Active
+ * no 0 1 Not Active
+ *
+ */
+#define OPT_WAIT_FOR_GETNODEINFO 0
+#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1
+#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0
+
+#define OPT_ENABLE_WD 1
+
+#define OPT_RESTART_TIMEOUT_MS 20000
+
+/* Reserved for the Booloader */
+#define OPT_BOOTLOADER_SIZE_IN_K (1024*64)
+
+/* Reserved for the application out of the total
+ * system flash minus the BOOTLOADER_SIZE_IN_K
+ */
+#define OPT_APPLICATION_RESERVER_IN_K 0
+
+#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K
+#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K))
+
+
+#define FLASH_BASE STM32_FLASH_BASE
+#define FLASH_SIZE STM32_FLASH_SIZE
+
+#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET)
+#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET)
+#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t)))
+#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t)))
+#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t)))
+
+/* If this board uses big flash that have large sectors */
+
+#define OPT_USE_YIELD
+
+/* Bootloader Option*****************************************************************
+ *
+ */
+#define GPIO_GETNODEINFO_JUMPER (GPIO_BOOT_CONFIG & ~GPIO_EXTI)
diff --git a/boards/ark/can-gps/src/can.c b/boards/ark/can-gps/src/can.c
new file mode 100644
index 000000000000..acc20252fab0
--- /dev/null
+++ b/boards/ark/can-gps/src/can.c
@@ -0,0 +1,130 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2021 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 can.c
+ *
+ * Board-specific CAN functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include
+
+#include
+#include
+
+#include
+#include
+
+#include "chip.h"
+#include "arm_arch.h"
+
+#include "stm32.h"
+#include "stm32_can.h"
+#include "board_config.h"
+
+#ifdef CONFIG_CAN
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
+# undef CONFIG_STM32_CAN2
+#endif
+
+#ifdef CONFIG_STM32_CAN1
+# define CAN_PORT 1
+#else
+# define CAN_PORT 2
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+int can_devinit(void);
+
+/************************************************************************************
+ * Name: can_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/can.
+ *
+ ************************************************************************************/
+
+int can_devinit(void)
+{
+ static bool initialized = false;
+ struct can_dev_s *can;
+ int ret;
+
+ /* Check if we have already initialized */
+
+ if (!initialized) {
+ /* Call stm32_caninitialize() to get an instance of the CAN interface */
+
+ can = stm32_caninitialize(CAN_PORT);
+
+ if (can == NULL) {
+ canerr("ERROR: Failed to get CAN interface\n");
+ return -ENODEV;
+ }
+
+ /* Register the CAN driver at "/dev/can0" */
+
+ ret = can_register("/dev/can0", can);
+
+ if (ret < 0) {
+ canerr("ERROR: can_register failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif
diff --git a/boards/ark/can-gps/src/i2c.cpp b/boards/ark/can-gps/src/i2c.cpp
new file mode 100644
index 000000000000..76486af73317
--- /dev/null
+++ b/boards/ark/can-gps/src/i2c.cpp
@@ -0,0 +1,39 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2021 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#include
+
+constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
+ initI2CBusInternal(1),
+ initI2CBusInternal(2),
+};
diff --git a/boards/ark/can-gps/src/init.c b/boards/ark/can-gps/src/init.c
new file mode 100644
index 000000000000..f6b32dd8d107
--- /dev/null
+++ b/boards/ark/can-gps/src/init.c
@@ -0,0 +1,163 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 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 init.c
+ *
+ * board specific early startup code. This file implements the
+ * board_app_initialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialization.
+ */
+
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+
+#include
+#include "board_config.h"
+#include "led.h"
+#include
+
+#include
+
+#include
+#include
+#include
+
+#include
+
+#include
+#include
+
+# if defined(FLASH_BASED_PARAMS)
+# include
+#endif
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the initialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_boardinitialize(void)
+{
+ watchdog_init();
+
+ /* configure pins */
+ const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
+ px4_gpio_init(gpio, arraySize(gpio));
+
+ // Configure SPI all interfaces GPIO & enable power.
+ stm32_spiinitialize();
+
+ // Check if button is held. If so go into gps passthrough mode
+ if (stm32_gpioread(GPIO_BTN_SAFETY)) {
+ rgb_led(128, 128, 128, 10);
+ stm32_configgpio(GPIO_USART1_TX_GPIO);
+ stm32_configgpio(GPIO_USART1_RX_GPIO);
+ stm32_configgpio(GPIO_USART2_TX_GPIO);
+ stm32_configgpio(GPIO_USART2_RX_GPIO);
+
+ while (1) {
+ watchdog_pet();
+ stm32_gpiowrite(GPIO_USART2_TX_GPIO, stm32_gpioread(GPIO_USART1_RX_GPIO));
+ stm32_gpiowrite(GPIO_USART1_TX_GPIO, stm32_gpioread(GPIO_USART2_RX_GPIO));
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: board_app_initialize
+ *
+ * Description:
+ * Perform application specific initialization. This function is never
+ * called directly from application code, but only indirectly via the
+ * (non-standard) boardctl() interface using the command BOARDIOC_INIT.
+ *
+ * Input Parameters:
+ * arg - The boardctl() argument is passed to the board_app_initialize()
+ * implementation without modification. The argument has no
+ * meaning to NuttX; the meaning of the argument is a contract
+ * between the board-specific initalization logic and the the
+ * matching application logic. The value cold be such things as a
+ * mode enumeration value, a set of DIP switch switch settings, a
+ * pointer to configuration data read from a file or serial FLASH,
+ * or whatever you would like to do with it. Every implementation
+ * should accept zero/NULL as a default configuration.
+ *
+ * Returned Value:
+ * Zero (OK) is returned on success; a negated errno value is returned on
+ * any failure to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+__EXPORT int board_app_initialize(uintptr_t arg)
+{
+ px4_platform_init();
+
+#if defined(FLASH_BASED_PARAMS)
+ static sector_descriptor_t params_sector_map[] = {
+ {2, 16 * 1024, 0x08008000},
+ {3, 16 * 1024, 0x0800C000},
+ {0, 0, 0},
+ };
+
+ /* Initialize the flashfs layer to use heap allocated memory */
+ int result = parameter_flashfs_init(params_sector_map, NULL, 0);
+
+ if (result != OK) {
+ syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
+ }
+
+#endif // FLASH_BASED_PARAMS
+
+ /* Configure the HW based on the manifest */
+
+ px4_platform_configure();
+
+ return OK;
+}
diff --git a/boards/ark/can-gps/src/led.c b/boards/ark/can-gps/src/led.c
new file mode 100644
index 000000000000..9a80cae08923
--- /dev/null
+++ b/boards/ark/can-gps/src/led.c
@@ -0,0 +1,124 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 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 led.c
+ *
+ * LED backend.
+ */
+
+#include
+
+#include
+
+#include "chip.h"
+#include "stm32_gpio.h"
+#include "board_config.h"
+
+#include
+#include
+
+#include "led.h"
+
+#define TMR_BASE STM32_TIM1_BASE
+#define TMR_FREQUENCY STM32_APB2_TIM1_CLKIN
+#define TMR_REG(o) (TMR_BASE+(o))
+
+void rgb_led(int r, int g, int b, int freqs)
+{
+
+ long fosc = TMR_FREQUENCY;
+ long prescale = 2048;
+ long p1s = fosc / prescale;
+ long p0p5s = p1s / 2;
+ uint16_t val;
+ static bool once = 0;
+
+ if (!once) {
+ once = 1;
+
+ /* Enabel Clock to Block */
+ modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN);
+
+ /* Reload */
+
+ val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET));
+ val |= ATIM_EGR_UG;
+ putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET));
+
+ /* Set Prescaler STM32_TIM_SETCLOCK */
+
+ putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET));
+
+ /* Enable STM32_TIM_SETMODE*/
+
+ putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET));
+
+
+ putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) | ATIM_CCMR1_OC1PE |
+ (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET));
+ putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET));
+ putreg16(ATIM_CCER_CC3E | ATIM_CCER_CC3P |
+ ATIM_CCER_CC2E | ATIM_CCER_CC2P |
+ ATIM_CCER_CC1E | ATIM_CCER_CC1P, TMR_REG(STM32_GTIM_CCER_OFFSET));
+
+
+ stm32_configgpio(GPIO_TIM1_CH1);
+ stm32_configgpio(GPIO_TIM1_CH2);
+ stm32_configgpio(GPIO_TIM1_CH3);
+
+ /* master output enable = on */
+ putreg16(ATIM_BDTR_MOE, (TMR_REG(STM32_ATIM_BDTR_OFFSET)));
+ }
+
+ long p = freqs == 0 ? p1s : p1s / freqs;
+ putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET));
+
+ p = freqs == 0 ? p1s + 1 : p0p5s / freqs;
+
+ putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR1_OFFSET));
+ putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET));
+ putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET));
+
+ val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET));
+
+ if (freqs == 0) {
+ val &= ~ATIM_CR1_CEN;
+
+ } else {
+ val |= ATIM_CR1_CEN;
+ }
+
+ putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET));
+
+}
diff --git a/boards/ark/can-gps/src/led.h b/boards/ark/can-gps/src/led.h
new file mode 100644
index 000000000000..b68e4aa70d0c
--- /dev/null
+++ b/boards/ark/can-gps/src/led.h
@@ -0,0 +1,37 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2015 PX4 Development Team. All rights reserved.
+ * Author: David Sidrane
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+__BEGIN_DECLS
+void rgb_led(int r, int g, int b, int freqs);
+__END_DECLS
diff --git a/boards/ark/can-gps/src/spi.cpp b/boards/ark/can-gps/src/spi.cpp
new file mode 100644
index 000000000000..baafb0354c6c
--- /dev/null
+++ b/boards/ark/can-gps/src/spi.cpp
@@ -0,0 +1,44 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2021 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#include
+#include
+#include
+
+constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
+ initSPIBus(SPI::Bus::SPI1, {
+ initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortB, GPIO::Pin0}, SPI::DRDY{GPIO::PortB, GPIO::Pin1}),
+ }),
+};
+
+static constexpr bool unused = validateSPIConfig(px4_spi_buses);
diff --git a/boards/ark/can-gps/uavcan_board_identity b/boards/ark/can-gps/uavcan_board_identity
new file mode 100644
index 000000000000..ca6d098e5942
--- /dev/null
+++ b/boards/ark/can-gps/uavcan_board_identity
@@ -0,0 +1,17 @@
+# UAVCAN boot loadable Module ID
+set(uavcanblid_sw_version_major 0)
+set(uavcanblid_sw_version_minor 1)
+add_definitions(
+ -DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major}
+ -DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor}
+)
+
+set(uavcanblid_hw_version_major 0)
+set(uavcanblid_hw_version_minor 81)
+set(uavcanblid_name "\"org.ark.can-gps\"")
+
+add_definitions(
+ -DHW_UAVCAN_NAME=${uavcanblid_name}
+ -DHW_VERSION_MAJOR=${uavcanblid_hw_version_major}
+ -DHW_VERSION_MINOR=${uavcanblid_hw_version_minor}
+)
diff --git a/boards/ark/can-rtk-gps/canbootloader.px4board b/boards/ark/can-rtk-gps/canbootloader.px4board
new file mode 100644
index 000000000000..46917280f6a4
--- /dev/null
+++ b/boards/ark/can-rtk-gps/canbootloader.px4board
@@ -0,0 +1,5 @@
+CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
+CONFIG_BOARD_ARCHITECTURE="cortex-m4"
+CONFIG_BOARD_ROMFSROOT=""
+CONFIG_BOARD_CONSTRAINED_MEMORY=y
+CONFIG_DRIVERS_BOOTLOADERS=y
diff --git a/boards/ark/can-rtk-gps/debug.px4board b/boards/ark/can-rtk-gps/debug.px4board
new file mode 100644
index 000000000000..dee7679749cc
--- /dev/null
+++ b/boards/ark/can-rtk-gps/debug.px4board
@@ -0,0 +1,5 @@
+CONFIG_BOARD_CONSTRAINED_FLASH=n
+CONFIG_BOARD_NO_HELP=n
+CONFIG_SYSTEMCMDS_REBOOT=y
+CONFIG_SYSTEMCMDS_TOP=y
+CONFIG_SYSTEMCMDS_UORB=y
diff --git a/boards/ark/can-rtk-gps/default.px4board b/boards/ark/can-rtk-gps/default.px4board
new file mode 100644
index 000000000000..8f69c01983e1
--- /dev/null
+++ b/boards/ark/can-rtk-gps/default.px4board
@@ -0,0 +1,30 @@
+CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
+CONFIG_BOARD_ARCHITECTURE="cortex-m4"
+CONFIG_BOARD_ROMFSROOT="cannode"
+CONFIG_BOARD_CONSTRAINED_FLASH=y
+CONFIG_BOARD_NO_HELP=y
+CONFIG_BOARD_CONSTRAINED_MEMORY=y
+CONFIG_DRIVERS_BAROMETER_BMP388=y
+CONFIG_DRIVERS_BOOTLOADERS=y
+CONFIG_DRIVERS_GPS=y
+CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
+CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y
+CONFIG_DRIVERS_SAFETY_BUTTON=y
+CONFIG_DRIVERS_TONE_ALARM=y
+CONFIG_BOARD_UAVCAN_INTERFACES=1
+CONFIG_DRIVERS_UAVCANNODE=y
+CONFIG_MODULES_GYRO_CALIBRATION=y
+CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
+CONFIG_MODULES_SENSORS=y
+# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set
+# CONFIG_SENSORS_VEHICLE_AIR_DATA is not set
+# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set
+CONFIG_SYSTEMCMDS_PARAM=y
+CONFIG_SYSTEMCMDS_PERF=y
+CONFIG_SYSTEMCMDS_REBOOT=y
+CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
+CONFIG_SYSTEMCMDS_TOP=y
+CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
+CONFIG_SYSTEMCMDS_UORB=y
+CONFIG_SYSTEMCMDS_VER=y
+CONFIG_SYSTEMCMDS_WORK_QUEUE=y
diff --git a/boards/ark/can-rtk-gps/firmware.prototype b/boards/ark/can-rtk-gps/firmware.prototype
new file mode 100644
index 000000000000..f8a96f3e7bf2
--- /dev/null
+++ b/boards/ark/can-rtk-gps/firmware.prototype
@@ -0,0 +1,13 @@
+{
+ "board_id": 82,
+ "magic": "PX4FWv1",
+ "description": "Firmware for the ARK RTK GPS board",
+ "image": "",
+ "build_time": 0,
+ "summary": "ARKRTKGPS",
+ "version": "0.1",
+ "image_size": 0,
+ "image_maxsize": 2080768,
+ "git_identity": "",
+ "board_revision": 0
+}
diff --git a/boards/ark/can-rtk-gps/init/rc.board_defaults b/boards/ark/can-rtk-gps/init/rc.board_defaults
new file mode 100644
index 000000000000..25bc347662c6
--- /dev/null
+++ b/boards/ark/can-rtk-gps/init/rc.board_defaults
@@ -0,0 +1,11 @@
+#!/bin/sh
+#
+# board specific defaults
+#------------------------------------------------------------------------------
+
+param set-default CBRK_IO_SAFETY 0
+param set-default CANNODE_GPS_RTCM 1
+param set-default MBE_ENABLE 1
+
+safety_button start
+tone_alarm start
diff --git a/boards/ark/can-rtk-gps/init/rc.board_sensors b/boards/ark/can-rtk-gps/init/rc.board_sensors
new file mode 100644
index 000000000000..d74d5f74b24d
--- /dev/null
+++ b/boards/ark/can-rtk-gps/init/rc.board_sensors
@@ -0,0 +1,11 @@
+#!/bin/sh
+#
+# board sensors init
+#------------------------------------------------------------------------------
+gps start -d /dev/ttyS0 -p ubx
+
+icm42688p -R 0 -s start
+
+bmp388 -I -b 2 start
+
+bmm150 -I -b 1 start
diff --git a/boards/ark/can-rtk-gps/nuttx-config/canbootloader/defconfig b/boards/ark/can-rtk-gps/nuttx-config/canbootloader/defconfig
new file mode 100644
index 000000000000..1ce0048f92ff
--- /dev/null
+++ b/boards/ark/can-rtk-gps/nuttx-config/canbootloader/defconfig
@@ -0,0 +1,61 @@
+#
+# This file is autogenerated: PLEASE DO NOT EDIT IT.
+#
+# You can use "make menuconfig" to make any modifications to the installed .config file.
+# You can then do "make savedefconfig" to generate a new defconfig file that includes your
+# modifications.
+#
+CONFIG_ARCH="arm"
+CONFIG_ARCH_BOARD_CUSTOM=y
+CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/can-rtk-gps/nuttx-config"
+CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
+CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARCH_CHIP_STM32=y
+CONFIG_ARCH_CHIP_STM32F412CE=y
+CONFIG_ARCH_INTERRUPTSTACK=4096
+CONFIG_ARMV7M_MEMCPY=y
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_BINFMT_DISABLE=y
+CONFIG_BOARD_LOOPSPERMSEC=16717
+CONFIG_C99_BOOL8=y
+CONFIG_CLOCK_MONOTONIC=y
+CONFIG_DEBUG_FULLOPT=y
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEFAULT_SMALL=y
+CONFIG_DISABLE_MOUNTPOINT=y
+CONFIG_DISABLE_MQUEUE=y
+CONFIG_DISABLE_PTHREAD=y
+CONFIG_EXPERIMENTAL=y
+CONFIG_FDCLONE_DISABLE=y
+CONFIG_FDCLONE_STDIO=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+CONFIG_IDLETHREAD_STACKSIZE=4096
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_LIBC_LONG_LONG=y
+CONFIG_LIBC_STRERROR=y
+CONFIG_LIB_BOARDCTL=y
+CONFIG_FS_PROCFS_MAX_TASKS=0
+CONFIG_MM_REGIONS=2
+CONFIG_NAME_MAX=0
+CONFIG_NUNGET_CHARS=0
+CONFIG_PREALLOC_TIMERS=0
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_RAM_SIZE=262144
+CONFIG_RAM_START=0x20010000
+CONFIG_RAW_BINARY=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_SIG_DEFAULT=y
+CONFIG_SIG_SIGALRM_ACTION=y
+CONFIG_SIG_SIGUSR1_ACTION=y
+CONFIG_SIG_SIGUSR2_ACTION=y
+CONFIG_STACK_COLORATION=y
+CONFIG_START_DAY=30
+CONFIG_START_MONTH=11
+CONFIG_STDIO_DISABLE_BUFFERING=y
+CONFIG_STM32_NOEXT_VECTORS=y
+CONFIG_STM32_TIM8=y
+CONFIG_TASK_NAME_SIZE=0
+CONFIG_USEC_PER_TICK=1000
+CONFIG_USERMAIN_STACKSIZE=4096
diff --git a/boards/ark/can-rtk-gps/nuttx-config/include/board.h b/boards/ark/can-rtk-gps/nuttx-config/include/board.h
new file mode 100644
index 000000000000..526392b92bbd
--- /dev/null
+++ b/boards/ark/can-rtk-gps/nuttx-config/include/board.h
@@ -0,0 +1,152 @@
+/************************************************************************************
+ * configs/px4fmu/include/board.h
+ * include/arch/board/board.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * 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 NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+#include "board_dma_map.h"
+
+#ifndef __ARCH_BOARD_BOARD_H
+#define __ARCH_BOARD_BOARD_H
+
+#include
+#ifndef __ASSEMBLY__
+# include
+#endif
+
+#include
+
+/* HSI - 8 MHz RC factory-trimmed
+ * LSI - 32 KHz RC
+ * HSE - 8 MHz Crystal
+ * LSE - not installed
+ */
+#define STM32_BOARD_USEHSE 1
+#define STM32_BOARD_XTAL 8000000
+#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
+
+#define STM32_HSI_FREQUENCY 16000000ul
+#define STM32_LSI_FREQUENCY 32000
+
+/* Main PLL Configuration */
+#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8)
+#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(384)
+#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_4
+#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(8)
+#define STM32_PLLCFG_PLLR RCC_PLLCFG_PLLR(2)
+
+#define STM32_RCC_PLLI2SCFGR_PLLI2SM RCC_PLLI2SCFGR_PLLI2SM(16)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SSRC RCC_PLLI2SCFGR_PLLI2SSRC(0) /* HSE or HSI depending on PLLSRC of PLLCFGR*/
+
+#define STM32_RCC_DCKCFGR2_CK48MSEL RCC_DCKCFGR2_CK48MSEL_PLL
+#define STM32_RCC_DCKCFGR2_FMPI2C1SEL RCC_DCKCFGR2_FMPI2C1SEL_APB
+#define STM32_RCC_DCKCFGR2_SDIOSEL RCC_DCKCFGR2_SDIOSEL_48MHZ
+
+#define STM32_SYSCLK_FREQUENCY 96000000ul
+
+/* AHB clock (HCLK) is SYSCLK (96MHz) */
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
+#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* Same as above, to satisfy compiler */
+
+/* APB1 clock (PCLK1) is HCLK/2 (48MHz) */
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
+
+/* Timers driven from APB1 will be twice PCLK1 (see page 112 of reference manual) */
+#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
+
+/* APB2 clock (PCLK2) is HCLK (96MHz) */
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK */
+#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY)
+
+/* Timers driven from APB2 will be PCLK2 since no prescale division */
+#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM9_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM10_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM11_CLKIN (STM32_PCLK2_FREQUENCY)
+
+/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx otherwise frequency is 2xAPBx. */
+#define BOARD_TIM2_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM3_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM4_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM5_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM6_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM7_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM8_FREQUENCY (2 * STM32_PCLK2_FREQUENCY)
+
+/* Alternate function pin selections ************************************************/
+
+/* UARTs */
+#define GPIO_USART1_RX GPIO_USART1_RX_2
+#define GPIO_USART1_TX GPIO_USART1_TX_3
+
+#define GPIO_USART2_RX GPIO_USART2_RX_1
+#define GPIO_USART2_TX GPIO_USART2_TX_1
+
+/* CAN */
+#define GPIO_CAN1_RX GPIO_CAN1_RX_1
+#define GPIO_CAN1_TX GPIO_CAN1_TX_1
+
+/* I2C */
+
+#define GPIO_MCU_I2C1_SCL
+#define GPIO_MCU_I2C1_SDA
+
+#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1
+#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1
+
+#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6)
+#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7)
+
+#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
+#define GPIO_I2C2_SDA GPIO_I2C2_SDA_4
+
+#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9)
+#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10)
+
+/* SPI */
+#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
+#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
+#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
+
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/boards/ark/can-rtk-gps/nuttx-config/include/board_dma_map.h b/boards/ark/can-rtk-gps/nuttx-config/include/board_dma_map.h
new file mode 100644
index 000000000000..efa3d824b2f6
--- /dev/null
+++ b/boards/ark/can-rtk-gps/nuttx-config/include/board_dma_map.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+// DMA1 Channel/Stream Selections
+//--------------------------------------------//---------------------------//----------------
+
+
+// DMA2 Channel/Stream Selections
+//--------------------------------------------//---------------------------//----------------
+#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1 // DMA2, Stream 0, Channel 3
+#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3
+#define DMACHAN_USART1_RX DMAMAP_USART1_RX_1 // DMA2, Stream 2, Channel 4
+#define DMAMAP_USART1_RX DMAMAP_USART1_RX_1
+//#define DMACHAN_USART1_TX DMAMAP_USART1_TX // DMA2, Stream 7, Channel 4
diff --git a/boards/ark/can-rtk-gps/nuttx-config/nsh/defconfig b/boards/ark/can-rtk-gps/nuttx-config/nsh/defconfig
new file mode 100644
index 000000000000..b669e9646327
--- /dev/null
+++ b/boards/ark/can-rtk-gps/nuttx-config/nsh/defconfig
@@ -0,0 +1,159 @@
+#
+# This file is autogenerated: PLEASE DO NOT EDIT IT.
+#
+# You can use "make menuconfig" to make any modifications to the installed .config file.
+# You can then do "make savedefconfig" to generate a new defconfig file that includes your
+# modifications.
+#
+# CONFIG_DISABLE_OS_API is not set
+# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
+# CONFIG_NSH_DISABLEBG is not set
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLE_DF is not set
+# CONFIG_NSH_DISABLE_EXEC is not set
+# CONFIG_NSH_DISABLE_EXIT is not set
+# CONFIG_NSH_DISABLE_GET is not set
+# CONFIG_NSH_DISABLE_ITEF is not set
+# CONFIG_NSH_DISABLE_LOOPS is not set
+# CONFIG_NSH_DISABLE_MKFATFS is not set
+# CONFIG_NSH_DISABLE_SEMICOLON is not set
+# CONFIG_NSH_DISABLE_TIME is not set
+# CONFIG_STM32_DMACAPABLE is not set
+CONFIG_ARCH="arm"
+CONFIG_ARCH_BOARD_CUSTOM=y
+CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/can-rtk-gps/nuttx-config"
+CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
+CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARCH_CHIP_STM32=y
+CONFIG_ARCH_CHIP_STM32F412CE=y
+CONFIG_ARCH_INTERRUPTSTACK=512
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_ARMV7M_MEMCPY=y
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_BOARDCTL_RESET=y
+CONFIG_BOARD_LOOPSPERMSEC=16717
+CONFIG_BOARD_RESET_ON_ASSERT=2
+CONFIG_BUILTIN=y
+CONFIG_C99_BOOL8=y
+CONFIG_CLOCK_MONOTONIC=y
+CONFIG_DEBUG_FULLOPT=y
+CONFIG_DEBUG_HARDFAULT_ALERT=y
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEFAULT_SMALL=y
+CONFIG_DEV_FIFO_SIZE=0
+CONFIG_DEV_PIPE_MAXSIZE=1024
+CONFIG_DEV_PIPE_SIZE=70
+CONFIG_FDCLONE_STDIO=y
+CONFIG_FS_BINFS=y
+CONFIG_FS_CROMFS=y
+CONFIG_FS_FAT=y
+CONFIG_FS_FATTIME=y
+CONFIG_FS_PROCFS=y
+CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
+CONFIG_FS_PROCFS_REGISTER=y
+CONFIG_FS_ROMFS=y
+CONFIG_GRAN=y
+CONFIG_GRAN_INTR=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+CONFIG_I2C=y
+CONFIG_I2C_RESET=y
+CONFIG_IDLETHREAD_STACKSIZE=750
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_LIBC_LONG_LONG=y
+CONFIG_LIBC_STRERROR=y
+CONFIG_MEMSET_64BIT=y
+CONFIG_MEMSET_OPTSPEED=y
+CONFIG_MM_REGIONS=2
+CONFIG_MTD=y
+CONFIG_MTD_BYTE_WRITE=y
+CONFIG_MTD_PARTITION=y
+CONFIG_MTD_RAMTRON=y
+CONFIG_NAME_MAX=40
+CONFIG_NSH_ARCHINIT=y
+CONFIG_NSH_ARGCAT=y
+CONFIG_NSH_BUILTIN_APPS=y
+CONFIG_NSH_CMDPARMS=y
+CONFIG_NSH_CROMFSETC=y
+CONFIG_NSH_DISABLE_IFCONFIG=y
+CONFIG_NSH_DISABLE_IFUPDOWN=y
+CONFIG_NSH_DISABLE_TELNETD=y
+CONFIG_NSH_LINELEN=128
+CONFIG_NSH_MAXARGUMENTS=15
+CONFIG_NSH_NESTDEPTH=8
+CONFIG_NSH_QUOTE=y
+CONFIG_NSH_ROMFSETC=y
+CONFIG_NSH_ROMFSSECTSIZE=128
+CONFIG_NSH_STRERROR=y
+CONFIG_NSH_VARS=y
+CONFIG_PIPES=y
+CONFIG_PREALLOC_TIMERS=50
+CONFIG_PRIORITY_INHERITANCE=y
+CONFIG_PTHREAD_MUTEX_ROBUST=y
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_RAMTRON_SETSPEED=y
+CONFIG_RAM_SIZE=262144
+CONFIG_RAM_START=0x20000000
+CONFIG_RAW_BINARY=y
+CONFIG_RTC_DATETIME=y
+CONFIG_SCHED_ATEXIT=y
+CONFIG_SCHED_HPWORK=y
+CONFIG_SCHED_HPWORKPRIORITY=249
+CONFIG_SCHED_HPWORKSTACKSIZE=1280
+CONFIG_SCHED_INSTRUMENTATION=y
+CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
+CONFIG_SCHED_LPWORK=y
+CONFIG_SCHED_LPWORKPRIORITY=50
+CONFIG_SCHED_LPWORKSTACKSIZE=1632
+CONFIG_SCHED_WAITPID=y
+CONFIG_SEM_PREALLOCHOLDERS=32
+CONFIG_SERIAL_TERMIOS=y
+CONFIG_SIG_DEFAULT=y
+CONFIG_SIG_SIGALRM_ACTION=y
+CONFIG_SIG_SIGUSR1_ACTION=y
+CONFIG_SIG_SIGUSR2_ACTION=y
+CONFIG_SIG_SIGWORK=4
+CONFIG_STACK_COLORATION=y
+CONFIG_START_DAY=30
+CONFIG_START_MONTH=11
+CONFIG_STDIO_BUFFER_SIZE=32
+CONFIG_STM32_ADC1=y
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=y
+CONFIG_STM32_FLASH_PREFETCH=y
+CONFIG_STM32_FLOWCONTROL_BROKEN=y
+CONFIG_STM32_I2C1=y
+CONFIG_STM32_I2C2=y
+CONFIG_STM32_JTAG_SW_ENABLE=y
+CONFIG_STM32_PWR=y
+CONFIG_STM32_RTC=y
+CONFIG_STM32_RTC_HSECLOCK=y
+CONFIG_STM32_RTC_MAGIC=0xfacefeee
+CONFIG_STM32_RTC_MAGIC_REG=1
+CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef
+CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
+CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
+CONFIG_STM32_SPI1=y
+CONFIG_STM32_SPI1_DMA=y
+CONFIG_STM32_SPI1_DMA_BUFFER=1024
+CONFIG_STM32_SPI_DMA=y
+CONFIG_STM32_TIM8=y
+CONFIG_STM32_USART1=y
+CONFIG_STM32_USART2=y
+CONFIG_STM32_USART_BREAKS=y
+CONFIG_STM32_WWDG=y
+CONFIG_SYSTEM_NSH=y
+CONFIG_TASK_NAME_SIZE=24
+CONFIG_USART1_BAUD=57600
+CONFIG_USART1_RXBUFSIZE=2000
+CONFIG_USART1_RXDMA=y
+CONFIG_USART1_TXBUFSIZE=2000
+CONFIG_USART2_BAUD=57600
+CONFIG_USART2_RXBUFSIZE=600
+CONFIG_USART2_SERIAL_CONSOLE=y
+CONFIG_USART2_TXBUFSIZE=1100
+CONFIG_USEC_PER_TICK=1000
+CONFIG_USERMAIN_STACKSIZE=2624
+CONFIG_USER_ENTRYPOINT="nsh_main"
diff --git a/boards/ark/can-rtk-gps/nuttx-config/scripts/canbootloader_script.ld b/boards/ark/can-rtk-gps/nuttx-config/scripts/canbootloader_script.ld
new file mode 100644
index 000000000000..cbf9fddc32dc
--- /dev/null
+++ b/boards/ark/can-rtk-gps/nuttx-config/scripts/canbootloader_script.ld
@@ -0,0 +1,134 @@
+/****************************************************************************
+ * nuttx-config/scripts/canbootloader_script.ld
+ *
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
+ * 256Kb of SRAM. SRAM is split up into three blocks:
+ *
+ * 1) 112Kb of SRAM beginning at address 0x2000:0000
+ * 2) 16Kb of SRAM beginning at address 0x2001:c000
+ * 3) 64Kb of SRAM beginning at address 0x2002:0000
+ * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000
+ *
+ * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
+ * where the code expects to begin execution by jumping to the entry point in
+ * the 0x0800:0000 address range.
+ *
+ * The first 0x10000 of flash is reserved for the bootloader.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08000000, LENGTH = 32K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
+}
+
+OUTPUT_ARCH(arm)
+
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/boards/ark/can-rtk-gps/nuttx-config/scripts/script.ld b/boards/ark/can-rtk-gps/nuttx-config/scripts/script.ld
new file mode 100644
index 000000000000..c63c74994199
--- /dev/null
+++ b/boards/ark/can-rtk-gps/nuttx-config/scripts/script.ld
@@ -0,0 +1,146 @@
+/****************************************************************************
+ * scripts/ld.script
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
+ * 256Kb of SRAM. SRAM is split up into three blocks:
+ *
+ * 1) 112Kb of SRAM beginning at address 0x2000:0000
+ * 2) 16Kb of SRAM beginning at address 0x2001:c000
+ * 3) 64Kb of SRAM beginning at address 0x2002:0000
+ * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000
+ *
+ * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
+ * where the code expects to begin execution by jumping to the entry point in
+ * the 0x0800:0000 address range.
+ *
+ * The first 0x10000 of flash is reserved for the bootloader.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08010000, LENGTH = 448K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
+}
+
+OUTPUT_ARCH(arm)
+
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+EXTERN(_bootdelay_signature)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ . = ALIGN(8);
+ /*
+ * This section positions the app_descriptor_t used
+ * by the make_can_boot_descriptor.py tool to set
+ * the application image's descriptor so that the
+ * uavcan bootloader has the ability to validate the
+ * image crc, size etc
+ */
+ KEEP(*(.app_descriptor))
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/boards/ark/can-rtk-gps/src/CMakeLists.txt b/boards/ark/can-rtk-gps/src/CMakeLists.txt
new file mode 100644
index 000000000000..06bd98156f22
--- /dev/null
+++ b/boards/ark/can-rtk-gps/src/CMakeLists.txt
@@ -0,0 +1,67 @@
+############################################################################
+#
+# Copyright (c) 2020 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader")
+
+ add_library(drivers_board
+ boot_config.h
+ boot.c
+ led.c
+ led.h
+ )
+ target_link_libraries(drivers_board
+ PRIVATE
+ nuttx_arch
+ nuttx_drivers
+ canbootloader
+ )
+ target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/canbootloader)
+
+else()
+ add_library(drivers_board
+ can.c
+ i2c.cpp
+ init.c
+ led.c
+ spi.cpp
+ )
+
+ target_link_libraries(drivers_board
+ PRIVATE
+ arch_spi
+ drivers__led # drv_led_start
+ nuttx_arch
+ nuttx_drivers
+ px4_layer
+ )
+endif()
diff --git a/boards/ark/can-rtk-gps/src/board_config.h b/boards/ark/can-rtk-gps/src/board_config.h
new file mode 100644
index 000000000000..2263956bae0f
--- /dev/null
+++ b/boards/ark/can-rtk-gps/src/board_config.h
@@ -0,0 +1,125 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file board_config.h
+ *
+ * board internal definitions
+ */
+
+#pragma once
+
+#include
+#include
+#include
+
+/* BUTTON */
+#define GPIO_BTN_SAFETY /* PB15 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN15)
+
+/* Safety LED */
+#define GPIO_LED_SAFETY /* PA1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN1)
+
+/* Tone alarm output. */
+#define TONE_ALARM_TIMER 2 /* timer 2 */
+#define TONE_ALARM_CHANNEL 1 /* channel 1 */
+#define GPIO_TONE_ALARM_IDLE /* PA0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_TONE_ALARM /* PA0 */ (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
+
+/* CAN Silent mode control */
+#define GPIO_CAN1_SILENT_S0 /* PB12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12)
+
+/* CAN termination software control */
+#define GPIO_CAN1_TERMINATION /* PB13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
+#define GPIO_CAN_TERM GPIO_CAN1_TERMINATION
+
+/* ICM42688p FSYNC */
+#define GPIO_42688P_FSYNC /* PB8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
+
+/* Boot config */
+#define GPIO_BOOT_CONFIG /* PC15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN15|GPIO_EXTI)
+
+/* LEDs are driven with open drain to support Anode to 5V or 3.3V */
+#define GPIO_TIM1_CH1 /* PA8 */ (GPIO_TIM1_CH1_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
+#define GPIO_TIM1_CH2 /* PA9 */ (GPIO_TIM1_CH2_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
+#define GPIO_TIM1_CH3 /* PA10 */ (GPIO_TIM1_CH3_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
+
+#define GPIO_I2C1_SCL_RESET /* PB6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN6)
+#define GPIO_I2C1_SDA_RESET /* PB7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN7)
+
+#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
+
+#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
+
+#define GPIO_USART1_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3)
+#define GPIO_USART1_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15)
+
+#define GPIO_USART2_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_USART2_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN2)
+
+#define FLASH_BASED_PARAMS
+
+/* High-resolution timer */
+#define HRT_TIMER 3 /* use timer 3 for the HRT */
+#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */
+
+#define PX4_GPIO_INIT_LIST { \
+ GPIO_BTN_SAFETY, \
+ GPIO_LED_SAFETY, \
+ GPIO_I2C1_SCL_RESET, \
+ GPIO_I2C1_SDA_RESET, \
+ GPIO_I2C2_SCL_RESET, \
+ GPIO_I2C2_SDA_RESET, \
+ GPIO_42688P_FSYNC, \
+ GPIO_BOOT_CONFIG, \
+ GPIO_CAN1_TX, \
+ GPIO_CAN1_RX, \
+ GPIO_CAN1_SILENT_S0, \
+ GPIO_CAN1_TERMINATION, \
+ }
+
+__BEGIN_DECLS
+
+#define BOARD_HAS_N_S_RGB_LED 1
+#define BOARD_MAX_LEDS BOARD_HAS_N_S_RGB_LED
+
+#ifndef __ASSEMBLY__
+
+extern void stm32_spiinitialize(void);
+
+#include
+
+#endif /* __ASSEMBLY__ */
+
+__END_DECLS
diff --git a/boards/ark/can-rtk-gps/src/boot.c b/boards/ark/can-rtk-gps/src/boot.c
new file mode 100644
index 000000000000..a26034e254f6
--- /dev/null
+++ b/boards/ark/can-rtk-gps/src/boot.c
@@ -0,0 +1,188 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 PX4 Development Team. All rights reserved.
+ * Author: Ben Dyer
+ * Pavel Kirienko
+ * David Sidrane
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include
+#include
+#include "boot_config.h"
+#include "board.h"
+
+#include
+#include
+#include
+
+#include
+#include "led.h"
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the initialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_boardinitialize(void)
+{
+ putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR);
+ stm32_configgpio(GPIO_CAN1_RX);
+ stm32_configgpio(GPIO_CAN1_TX);
+ stm32_configgpio(GPIO_CAN1_SILENT_S0);
+ stm32_configgpio(GPIO_CAN1_TERMINATION);
+ putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
+ putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
+
+#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
+ stm32_configgpio(GPIO_GETNODEINFO_JUMPER);
+#endif
+
+}
+
+/************************************************************************************
+ * Name: board_deinitialize
+ *
+ * Description:
+ * This function is called by the bootloader code prior to booting
+ * the application. Is should place the HW into an benign initialized state.
+ *
+ ************************************************************************************/
+
+void board_deinitialize(void)
+{
+ putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
+}
+
+/****************************************************************************
+ * Name: board_get_product_name
+ *
+ * Description:
+ * Called to retrieve the product name. The returned value is a assumed
+ * to be written to a pascal style string that will be length prefixed
+ * and not null terminated
+ *
+ * Input Parameters:
+ * product_name - A pointer to a buffer to write the name.
+ * maxlen - The maximum number of charter that can be written
+ *
+ * Returned Value:
+ * The length of characters written to the buffer.
+ *
+ ****************************************************************************/
+
+uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen)
+{
+ DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME));
+ memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME));
+ return UAVCAN_STRLEN(HW_UAVCAN_NAME);
+}
+
+/****************************************************************************
+ * Name: board_get_hardware_version
+ *
+ * Description:
+ * Called to retrieve the hardware version information. The function
+ * will first initialize the the callers struct to all zeros.
+ *
+ * Input Parameters:
+ * hw_version - A pointer to a uavcan_hardwareversion_t.
+ *
+ * Returned Value:
+ * Length of the unique_id
+ *
+ ****************************************************************************/
+
+size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version)
+{
+ memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t));
+
+ hw_version->major = HW_VERSION_MAJOR;
+ hw_version->minor = HW_VERSION_MINOR;
+
+ return board_get_mfguid(*(mfguid_t *) hw_version->unique_id);
+}
+
+/****************************************************************************
+ * Name: board_indicate
+ *
+ * Description:
+ * Provides User feedback to indicate the state of the bootloader
+ * on board specific hardware.
+ *
+ * Input Parameters:
+ * indication - A member of the uiindication_t
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)}
+
+typedef begin_packed_struct struct led_t {
+ uint8_t red;
+ uint8_t green;
+ uint8_t blue;
+ uint8_t hz;
+} end_packed_struct led_t;
+
+static const led_t i2l[] = {
+
+ led(0, off, 0, 0, 0, 0),
+ led(1, reset, 128, 128, 128, 30),
+ led(2, autobaud_start, 0, 128, 0, 1),
+ led(3, autobaud_end, 0, 128, 0, 2),
+ led(4, allocation_start, 0, 0, 64, 2),
+ led(5, allocation_end, 0, 128, 64, 3),
+ led(6, fw_update_start, 32, 128, 64, 3),
+ led(7, fw_update_erase_fail, 32, 128, 32, 3),
+ led(8, fw_update_invalid_response, 64, 0, 0, 1),
+ led(9, fw_update_timeout, 64, 0, 0, 2),
+ led(a, fw_update_invalid_crc, 64, 0, 0, 4),
+ led(b, jump_to_app, 0, 128, 0, 10),
+
+};
+
+void board_indicate(uiindication_t indication)
+{
+ rgb_led(i2l[indication].red,
+ i2l[indication].green,
+ i2l[indication].blue,
+ i2l[indication].hz);
+}
diff --git a/boards/ark/can-rtk-gps/src/boot_config.h b/boards/ark/can-rtk-gps/src/boot_config.h
new file mode 100644
index 000000000000..eab3c76c6c13
--- /dev/null
+++ b/boards/ark/can-rtk-gps/src/boot_config.h
@@ -0,0 +1,130 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 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 boot_config.h
+ *
+ * bootloader definitions that configures the behavior and options
+ * of the Boot loader
+ * This file is relies on the parent folder's boot_config.h file and defines
+ * different usages of the hardware for bootloading
+ */
+
+#pragma once
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+/* Bring in the board_config.h definitions
+ * todo:make this be pulled in from a targed's build
+ * files in nuttx*/
+
+#include "board_config.h"
+#include "uavcan.h"
+#include
+
+#include
+
+#include
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
+
+//todo:wrap OPT_x in in ifdefs for command line definitions
+#define OPT_TBOOT_MS 5000
+#define OPT_NODE_STATUS_RATE_MS 800
+#define OPT_NODE_INFO_RATE_MS 50
+#define OPT_BL_NUMBER_TIMERS 7
+
+/*
+ * This Option set is set to 1 ensure a provider of firmware has an
+ * opportunity update the node's firmware.
+ * This Option is the default policy and can be overridden by
+ * a jumper
+ * When this Policy is set, the node will ignore tboot and
+ * wait indefinitely for a GetNodeInfo request before booting.
+ *
+ * OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow
+ * the polarity of the jumper to be True Active
+ *
+ * wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
+ * Jumper
+ * yes 1 0 x
+ * yes 1 1 Active
+ * no 1 1 Not Active
+ * no 0 0 X
+ * yes 0 1 Active
+ * no 0 1 Not Active
+ *
+ */
+#define OPT_WAIT_FOR_GETNODEINFO 0
+#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1
+#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0
+
+#define OPT_ENABLE_WD 1
+
+#define OPT_RESTART_TIMEOUT_MS 20000
+
+/* Reserved for the Booloader */
+#define OPT_BOOTLOADER_SIZE_IN_K (1024*64)
+
+/* Reserved for the application out of the total
+ * system flash minus the BOOTLOADER_SIZE_IN_K
+ */
+#define OPT_APPLICATION_RESERVER_IN_K 0
+
+#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K
+#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K))
+
+
+#define FLASH_BASE STM32_FLASH_BASE
+#define FLASH_SIZE STM32_FLASH_SIZE
+
+#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET)
+#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET)
+#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t)))
+#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t)))
+#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t)))
+
+/* If this board uses big flash that have large sectors */
+
+#define OPT_USE_YIELD
+
+/* Bootloader Option*****************************************************************
+ *
+ */
+#define GPIO_GETNODEINFO_JUMPER (GPIO_BOOT_CONFIG & ~GPIO_EXTI)
diff --git a/boards/ark/can-rtk-gps/src/can.c b/boards/ark/can-rtk-gps/src/can.c
new file mode 100644
index 000000000000..acc20252fab0
--- /dev/null
+++ b/boards/ark/can-rtk-gps/src/can.c
@@ -0,0 +1,130 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2021 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 can.c
+ *
+ * Board-specific CAN functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include
+
+#include
+#include
+
+#include
+#include
+
+#include "chip.h"
+#include "arm_arch.h"
+
+#include "stm32.h"
+#include "stm32_can.h"
+#include "board_config.h"
+
+#ifdef CONFIG_CAN
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
+# undef CONFIG_STM32_CAN2
+#endif
+
+#ifdef CONFIG_STM32_CAN1
+# define CAN_PORT 1
+#else
+# define CAN_PORT 2
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+int can_devinit(void);
+
+/************************************************************************************
+ * Name: can_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/can.
+ *
+ ************************************************************************************/
+
+int can_devinit(void)
+{
+ static bool initialized = false;
+ struct can_dev_s *can;
+ int ret;
+
+ /* Check if we have already initialized */
+
+ if (!initialized) {
+ /* Call stm32_caninitialize() to get an instance of the CAN interface */
+
+ can = stm32_caninitialize(CAN_PORT);
+
+ if (can == NULL) {
+ canerr("ERROR: Failed to get CAN interface\n");
+ return -ENODEV;
+ }
+
+ /* Register the CAN driver at "/dev/can0" */
+
+ ret = can_register("/dev/can0", can);
+
+ if (ret < 0) {
+ canerr("ERROR: can_register failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif
diff --git a/boards/ark/can-rtk-gps/src/i2c.cpp b/boards/ark/can-rtk-gps/src/i2c.cpp
new file mode 100644
index 000000000000..76486af73317
--- /dev/null
+++ b/boards/ark/can-rtk-gps/src/i2c.cpp
@@ -0,0 +1,39 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2021 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#include
+
+constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
+ initI2CBusInternal(1),
+ initI2CBusInternal(2),
+};
diff --git a/boards/ark/can-rtk-gps/src/init.c b/boards/ark/can-rtk-gps/src/init.c
new file mode 100644
index 000000000000..7405575781e5
--- /dev/null
+++ b/boards/ark/can-rtk-gps/src/init.c
@@ -0,0 +1,169 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 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 init.c
+ *
+ * board specific early startup code. This file implements the
+ * board_app_initialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialization.
+ */
+
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+
+#include
+#include "board_config.h"
+#include "led.h"
+#include
+
+#include
+
+#include
+#include
+#include
+
+#include
+
+#include
+#include
+
+# if defined(FLASH_BASED_PARAMS)
+# include
+#endif
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the initialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_boardinitialize(void)
+{
+ watchdog_init();
+
+ /* configure pins */
+ const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
+ px4_gpio_init(gpio, arraySize(gpio));
+
+ // Configure SPI all interfaces GPIO & enable power.
+ stm32_spiinitialize();
+
+ // Check if button is held. If so go into gps passthrough mode
+ if (stm32_gpioread(GPIO_BTN_SAFETY)) {
+ rgb_led(128, 128, 128, 10);
+ stm32_configgpio(GPIO_USART1_TX_GPIO);
+ stm32_configgpio(GPIO_USART1_RX_GPIO);
+ stm32_configgpio(GPIO_USART2_TX_GPIO);
+ stm32_configgpio(GPIO_USART2_RX_GPIO);
+
+ while (1) {
+ watchdog_pet();
+ stm32_gpiowrite(GPIO_USART2_TX_GPIO, stm32_gpioread(GPIO_USART1_RX_GPIO));
+ stm32_gpiowrite(GPIO_USART1_TX_GPIO, stm32_gpioread(GPIO_USART2_RX_GPIO));
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: board_app_initialize
+ *
+ * Description:
+ * Perform application specific initialization. This function is never
+ * called directly from application code, but only indirectly via the
+ * (non-standard) boardctl() interface using the command BOARDIOC_INIT.
+ *
+ * Input Parameters:
+ * arg - The boardctl() argument is passed to the board_app_initialize()
+ * implementation without modification. The argument has no
+ * meaning to NuttX; the meaning of the argument is a contract
+ * between the board-specific initalization logic and the the
+ * matching application logic. The value cold be such things as a
+ * mode enumeration value, a set of DIP switch switch settings, a
+ * pointer to configuration data read from a file or serial FLASH,
+ * or whatever you would like to do with it. Every implementation
+ * should accept zero/NULL as a default configuration.
+ *
+ * Returned Value:
+ * Zero (OK) is returned on success; a negated errno value is returned on
+ * any failure to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+__EXPORT int board_app_initialize(uintptr_t arg)
+{
+ px4_platform_init();
+
+#if defined(SERIAL_HAVE_RXDMA)
+ // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
+ static struct hrt_call serial_dma_call;
+ hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
+#endif
+
+#if defined(FLASH_BASED_PARAMS)
+ static sector_descriptor_t params_sector_map[] = {
+ {2, 16 * 1024, 0x08008000},
+ {3, 16 * 1024, 0x0800C000},
+ {0, 0, 0},
+ };
+
+ /* Initialize the flashfs layer to use heap allocated memory */
+ int result = parameter_flashfs_init(params_sector_map, NULL, 0);
+
+ if (result != OK) {
+ syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
+ }
+
+#endif // FLASH_BASED_PARAMS
+
+ /* Configure the HW based on the manifest */
+
+ px4_platform_configure();
+
+ return OK;
+}
diff --git a/boards/ark/can-rtk-gps/src/led.c b/boards/ark/can-rtk-gps/src/led.c
new file mode 100644
index 000000000000..9a80cae08923
--- /dev/null
+++ b/boards/ark/can-rtk-gps/src/led.c
@@ -0,0 +1,124 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 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 led.c
+ *
+ * LED backend.
+ */
+
+#include
+
+#include
+
+#include "chip.h"
+#include "stm32_gpio.h"
+#include "board_config.h"
+
+#include
+#include
+
+#include "led.h"
+
+#define TMR_BASE STM32_TIM1_BASE
+#define TMR_FREQUENCY STM32_APB2_TIM1_CLKIN
+#define TMR_REG(o) (TMR_BASE+(o))
+
+void rgb_led(int r, int g, int b, int freqs)
+{
+
+ long fosc = TMR_FREQUENCY;
+ long prescale = 2048;
+ long p1s = fosc / prescale;
+ long p0p5s = p1s / 2;
+ uint16_t val;
+ static bool once = 0;
+
+ if (!once) {
+ once = 1;
+
+ /* Enabel Clock to Block */
+ modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN);
+
+ /* Reload */
+
+ val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET));
+ val |= ATIM_EGR_UG;
+ putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET));
+
+ /* Set Prescaler STM32_TIM_SETCLOCK */
+
+ putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET));
+
+ /* Enable STM32_TIM_SETMODE*/
+
+ putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET));
+
+
+ putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) | ATIM_CCMR1_OC1PE |
+ (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET));
+ putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET));
+ putreg16(ATIM_CCER_CC3E | ATIM_CCER_CC3P |
+ ATIM_CCER_CC2E | ATIM_CCER_CC2P |
+ ATIM_CCER_CC1E | ATIM_CCER_CC1P, TMR_REG(STM32_GTIM_CCER_OFFSET));
+
+
+ stm32_configgpio(GPIO_TIM1_CH1);
+ stm32_configgpio(GPIO_TIM1_CH2);
+ stm32_configgpio(GPIO_TIM1_CH3);
+
+ /* master output enable = on */
+ putreg16(ATIM_BDTR_MOE, (TMR_REG(STM32_ATIM_BDTR_OFFSET)));
+ }
+
+ long p = freqs == 0 ? p1s : p1s / freqs;
+ putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET));
+
+ p = freqs == 0 ? p1s + 1 : p0p5s / freqs;
+
+ putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR1_OFFSET));
+ putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET));
+ putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET));
+
+ val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET));
+
+ if (freqs == 0) {
+ val &= ~ATIM_CR1_CEN;
+
+ } else {
+ val |= ATIM_CR1_CEN;
+ }
+
+ putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET));
+
+}
diff --git a/boards/ark/can-rtk-gps/src/led.h b/boards/ark/can-rtk-gps/src/led.h
new file mode 100644
index 000000000000..b68e4aa70d0c
--- /dev/null
+++ b/boards/ark/can-rtk-gps/src/led.h
@@ -0,0 +1,37 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2015 PX4 Development Team. All rights reserved.
+ * Author: David Sidrane
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+__BEGIN_DECLS
+void rgb_led(int r, int g, int b, int freqs);
+__END_DECLS
diff --git a/boards/ark/can-rtk-gps/src/spi.cpp b/boards/ark/can-rtk-gps/src/spi.cpp
new file mode 100644
index 000000000000..baafb0354c6c
--- /dev/null
+++ b/boards/ark/can-rtk-gps/src/spi.cpp
@@ -0,0 +1,44 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2021 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#include
+#include
+#include
+
+constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
+ initSPIBus(SPI::Bus::SPI1, {
+ initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortB, GPIO::Pin0}, SPI::DRDY{GPIO::PortB, GPIO::Pin1}),
+ }),
+};
+
+static constexpr bool unused = validateSPIConfig(px4_spi_buses);
diff --git a/boards/ark/can-rtk-gps/uavcan_board_identity b/boards/ark/can-rtk-gps/uavcan_board_identity
new file mode 100644
index 000000000000..5db21a4ffb03
--- /dev/null
+++ b/boards/ark/can-rtk-gps/uavcan_board_identity
@@ -0,0 +1,17 @@
+# UAVCAN boot loadable Module ID
+set(uavcanblid_sw_version_major 0)
+set(uavcanblid_sw_version_minor 1)
+add_definitions(
+ -DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major}
+ -DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor}
+)
+
+set(uavcanblid_hw_version_major 0)
+set(uavcanblid_hw_version_minor 82)
+set(uavcanblid_name "\"org.ark.can-rtk-gps\"")
+
+add_definitions(
+ -DHW_UAVCAN_NAME=${uavcanblid_name}
+ -DHW_VERSION_MAJOR=${uavcanblid_hw_version_major}
+ -DHW_VERSION_MINOR=${uavcanblid_hw_version_minor}
+)
diff --git a/boards/ark/cannode/canbootloader.px4board b/boards/ark/cannode/canbootloader.px4board
new file mode 100644
index 000000000000..51093ca3386c
--- /dev/null
+++ b/boards/ark/cannode/canbootloader.px4board
@@ -0,0 +1,6 @@
+CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
+CONFIG_BOARD_ARCHITECTURE="cortex-m4"
+CONFIG_BOARD_ROMFSROOT=""
+CONFIG_BOARD_CONSTRAINED_MEMORY=y
+CONFIG_DRIVERS_BOOTLOADERS=y
+CONFIG_NSH_BUILTIN_APPS=y
diff --git a/boards/ark/cannode/default.px4board b/boards/ark/cannode/default.px4board
new file mode 100644
index 000000000000..14493945baf2
--- /dev/null
+++ b/boards/ark/cannode/default.px4board
@@ -0,0 +1,37 @@
+CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
+CONFIG_BOARD_ARCHITECTURE="cortex-m4"
+CONFIG_BOARD_ROMFSROOT="cannode"
+CONFIG_BOARD_CONSTRAINED_FLASH=y
+#CONFIG_BOARD_NO_HELP=y
+CONFIG_BOARD_CONSTRAINED_MEMORY=y
+CONFIG_BOARD_EXTERNAL_METADATA=y
+CONFIG_COMMON_BAROMETERS=y
+CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
+CONFIG_COMMON_DISTANCE_SENSOR=y
+CONFIG_COMMON_HYGROMETERS=y
+CONFIG_COMMON_MAGNETOMETER=y
+CONFIG_COMMON_LIGHT=y
+CONFIG_DRIVERS_BATT_SMBUS=y
+CONFIG_DRIVERS_BOOTLOADERS=y
+CONFIG_DRIVERS_GPS=y
+CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
+CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
+CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
+CONFIG_DRIVERS_IRLOCK=y
+CONFIG_DRIVERS_PWM_OUT=y
+CONFIG_BOARD_UAVCAN_INTERFACES=1
+CONFIG_DRIVERS_UAVCANNODE=y
+CONFIG_MODULES_CONTROL_ALLOCATOR=y
+#CONFIG_MODULES_SENSORS=y
+CONFIG_NSH_BUILTIN_APPS=y
+CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
+CONFIG_SYSTEMCMDS_I2CDETECT=y
+CONFIG_SYSTEMCMDS_LED_CONTROL=y
+CONFIG_SYSTEMCMDS_MIXER=y
+CONFIG_SYSTEMCMDS_UORB=y
+CONFIG_SYSTEMCMDS_PARAM=y
+CONFIG_SYSTEMCMDS_TOP=y
+CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
+CONFIG_SYSTEMCMDS_PWM=y
+CONFIG_SYSTEMCMDS_REBOOT=y
+CONFIG_SYSTEMCMDS_WORK_QUEUE=y
diff --git a/boards/ark/cannode/firmware.prototype b/boards/ark/cannode/firmware.prototype
new file mode 100644
index 000000000000..8b149d8c5f8b
--- /dev/null
+++ b/boards/ark/cannode/firmware.prototype
@@ -0,0 +1,13 @@
+{
+ "board_id": 83,
+ "magic": "PX4FWv1",
+ "description": "Firmware for the ARK CANnode board",
+ "image": "",
+ "build_time": 0,
+ "summary": "ARKCANNODE",
+ "version": "0.1",
+ "image_size": 0,
+ "image_maxsize": 2080768,
+ "git_identity": "",
+ "board_revision": 0
+}
diff --git a/boards/ark/cannode/init/rc.board_defaults b/boards/ark/cannode/init/rc.board_defaults
new file mode 100644
index 000000000000..ba6faf3d0a49
--- /dev/null
+++ b/boards/ark/cannode/init/rc.board_defaults
@@ -0,0 +1,7 @@
+#!/bin/sh
+#
+# board specific defaults
+#------------------------------------------------------------------------------
+pwm_out start
+
+control_allocator start
diff --git a/boards/ark/cannode/init/rc.board_sensors b/boards/ark/cannode/init/rc.board_sensors
new file mode 100644
index 000000000000..bbddf5f5d49a
--- /dev/null
+++ b/boards/ark/cannode/init/rc.board_sensors
@@ -0,0 +1,118 @@
+#!/bin/sh
+#
+# board sensors init
+#------------------------------------------------------------------------------
+icm42688p -R 0 -s start
+
+if param compare -s SENS_EN_BATT 1
+then
+ batt_smbus start -X
+fi
+
+# Lidar-Lite on I2C
+if param compare -s SENS_EN_LL40LS 2
+then
+ ll40ls start -X
+fi
+
+# mappydot lidar sensor
+if param compare -s SENS_EN_MPDT 1
+then
+ mappydot start -X
+fi
+
+# mb12xx sonar sensor
+if param greater -s SENS_EN_MB12XX 0
+then
+ mb12xx start -X
+fi
+
+# Lightware i2c lidar sensor
+if param greater -s SENS_EN_SF1XX 0
+then
+ lightware_laser_i2c start -X
+fi
+
+# vl53l1x i2c distance sensor
+if param compare -s SENS_EN_VL53L1X 1
+then
+ vl53l1x start -X
+fi
+
+# ADIS16448 spi external IMU
+if param compare -s SENS_EN_ADIS164X 1
+then
+ if param compare -s SENS_OR_ADIS164X 0
+ then
+ adis16448 -S start
+ fi
+ if param compare -s SENS_OR_ADIS164X 4
+ then
+ adis16448 -S start -R 4
+ fi
+fi
+
+# Eagle Tree airspeed sensor external I2C
+if param compare -s SENS_EN_ETSASPD 1
+then
+ ets_airspeed start -X
+fi
+
+# Sensirion SDP3X differential pressure sensor external I2C
+if param compare -s SENS_EN_SDP3X 1
+then
+ if ! sdp3x start -X
+ then
+ # try another common address
+ sdp3x start -X -a 0x22
+ fi
+fi
+
+# SHT3x temperature and hygrometer sensor, external I2C
+if param compare -s SENS_EN_SHT3X 1
+then
+ sht3x start -X
+ sht3x start -X -a 0x45
+fi
+
+# TE MS4525DO differential pressure sensor external I2C
+if param compare -s SENS_EN_MS4525DO 1
+then
+ ms4525do start -X
+fi
+
+# TE MS5525DSO differential pressure sensor external I2C
+if param compare -s SENS_EN_MS5525DS 1
+then
+ ms5525dso start -X
+fi
+
+# IR-LOCK sensor external I2C
+if param compare -s SENS_EN_IRLOCK 1
+then
+ irlock start -X
+fi
+
+# SPL06 sensor external I2C
+if param compare -s SENS_EN_SPL06 1
+then
+ spl06 -X start
+ spl06 -X -a 0x77 start
+fi
+
+gps start -d /dev/ttyS0 -p ubx
+
+# probe for optional external I2C devices
+icm20948_i2c_passthrough -X -q start
+
+# compasses
+hmc5883 -T -X -q start
+ist8308 -X -q start
+ist8310 -X -q start
+lis2mdl -X -q start
+lis3mdl -X -q start
+qmc5883l -X -q start
+rm3100 -X -q start
+
+# start last (wait for possible icm20948 passthrough mode)
+ak09916 -X -q start
diff --git a/boards/ark/cannode/nuttx-config/canbootloader/defconfig b/boards/ark/cannode/nuttx-config/canbootloader/defconfig
new file mode 100644
index 000000000000..2e99504e20a9
--- /dev/null
+++ b/boards/ark/cannode/nuttx-config/canbootloader/defconfig
@@ -0,0 +1,61 @@
+#
+# This file is autogenerated: PLEASE DO NOT EDIT IT.
+#
+# You can use "make menuconfig" to make any modifications to the installed .config file.
+# You can then do "make savedefconfig" to generate a new defconfig file that includes your
+# modifications.
+#
+CONFIG_ARCH="arm"
+CONFIG_ARCH_BOARD_CUSTOM=y
+CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/cannode/nuttx-config"
+CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
+CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARCH_CHIP_STM32=y
+CONFIG_ARCH_CHIP_STM32F412CE=y
+CONFIG_ARCH_INTERRUPTSTACK=4096
+CONFIG_ARMV7M_MEMCPY=y
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_BINFMT_DISABLE=y
+CONFIG_BOARD_LOOPSPERMSEC=16717
+CONFIG_C99_BOOL8=y
+CONFIG_CLOCK_MONOTONIC=y
+CONFIG_DEBUG_FULLOPT=y
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEFAULT_SMALL=y
+CONFIG_DISABLE_MOUNTPOINT=y
+CONFIG_DISABLE_MQUEUE=y
+CONFIG_DISABLE_PTHREAD=y
+CONFIG_EXPERIMENTAL=y
+CONFIG_FDCLONE_DISABLE=y
+CONFIG_FDCLONE_STDIO=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+CONFIG_IDLETHREAD_STACKSIZE=4096
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_LIBC_LONG_LONG=y
+CONFIG_LIBC_STRERROR=y
+CONFIG_LIB_BOARDCTL=y
+CONFIG_FS_PROCFS_MAX_TASKS=0
+CONFIG_MM_REGIONS=2
+CONFIG_NAME_MAX=0
+CONFIG_NUNGET_CHARS=0
+CONFIG_PREALLOC_TIMERS=0
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_RAM_SIZE=262144
+CONFIG_RAM_START=0x20010000
+CONFIG_RAW_BINARY=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_SIG_DEFAULT=y
+CONFIG_SIG_SIGALRM_ACTION=y
+CONFIG_SIG_SIGUSR1_ACTION=y
+CONFIG_SIG_SIGUSR2_ACTION=y
+CONFIG_STACK_COLORATION=y
+CONFIG_START_DAY=30
+CONFIG_START_MONTH=11
+CONFIG_STDIO_DISABLE_BUFFERING=y
+CONFIG_STM32_FLASH_CONFIG_G=y
+CONFIG_STM32_NOEXT_VECTORS=y
+CONFIG_TASK_NAME_SIZE=0
+CONFIG_USEC_PER_TICK=1000
+CONFIG_USERMAIN_STACKSIZE=4096
diff --git a/boards/ark/cannode/nuttx-config/include/board.h b/boards/ark/cannode/nuttx-config/include/board.h
new file mode 100644
index 000000000000..aa067118540a
--- /dev/null
+++ b/boards/ark/cannode/nuttx-config/include/board.h
@@ -0,0 +1,149 @@
+/************************************************************************************
+ * configs/px4fmu/include/board.h
+ * include/arch/board/board.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * 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 NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+#include "board_dma_map.h"
+
+#ifndef __ARCH_BOARD_BOARD_H
+#define __ARCH_BOARD_BOARD_H
+
+#include
+#ifndef __ASSEMBLY__
+# include
+#endif
+
+#include
+
+/* HSI - 8 MHz RC factory-trimmed
+ * LSI - 32 KHz RC
+ * HSE - 8 MHz Crystal
+ * LSE - not installed
+ */
+#define STM32_BOARD_USEHSE 1
+#define STM32_BOARD_XTAL 8000000
+#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
+
+#define STM32_HSI_FREQUENCY 16000000ul
+#define STM32_LSI_FREQUENCY 32000
+
+/* Main PLL Configuration */
+#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8)
+#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(384)
+#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_4
+#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(8)
+#define STM32_PLLCFG_PLLR RCC_PLLCFG_PLLR(2)
+
+#define STM32_RCC_PLLI2SCFGR_PLLI2SM RCC_PLLI2SCFGR_PLLI2SM(16)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SSRC RCC_PLLI2SCFGR_PLLI2SSRC(0) /* HSE or HSI depending on PLLSRC of PLLCFGR*/
+
+#define STM32_RCC_DCKCFGR2_CK48MSEL RCC_DCKCFGR2_CK48MSEL_PLL
+#define STM32_RCC_DCKCFGR2_FMPI2C1SEL RCC_DCKCFGR2_FMPI2C1SEL_APB
+#define STM32_RCC_DCKCFGR2_SDIOSEL RCC_DCKCFGR2_SDIOSEL_48MHZ
+
+#define STM32_SYSCLK_FREQUENCY 96000000ul
+
+/* AHB clock (HCLK) is SYSCLK (96MHz) */
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
+#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* Same as above, to satisfy compiler */
+
+/* APB1 clock (PCLK1) is HCLK/2 (48MHz) */
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
+
+/* Timers driven from APB1 will be twice PCLK1 (see page 112 of reference manual) */
+#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
+
+/* APB2 clock (PCLK2) is HCLK (96MHz) */
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK */
+#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY)
+
+/* Timers driven from APB2 will be PCLK2 since no prescale division */
+#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM9_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM10_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM11_CLKIN (STM32_PCLK2_FREQUENCY)
+
+/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx otherwise frequency is 2xAPBx. */
+#define BOARD_TIM2_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM3_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM4_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM5_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM6_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM7_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
+#define BOARD_TIM8_FREQUENCY (2 * STM32_PCLK2_FREQUENCY)
+
+/* Alternate function pin selections ************************************************/
+
+/* UARTs */
+#define GPIO_USART1_RX GPIO_USART1_RX_2
+#define GPIO_USART1_TX GPIO_USART1_TX_3
+
+#define GPIO_USART2_RX GPIO_USART2_RX_1
+#define GPIO_USART2_TX GPIO_USART2_TX_1
+
+/* CAN */
+#define GPIO_CAN1_RX GPIO_CAN1_RX_1
+#define GPIO_CAN1_TX GPIO_CAN1_TX_1
+
+/* SPI */
+#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
+#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
+#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
+
+#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */
+#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */
+#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2 /* PB13 */
+
+/* I2C */
+#define GPIO_MCU_I2C1_SCL
+#define GPIO_MCU_I2C1_SDA
+
+#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1
+#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
+
+#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6)
+#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7)
+
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/boards/ark/cannode/nuttx-config/include/board_dma_map.h b/boards/ark/cannode/nuttx-config/include/board_dma_map.h
new file mode 100644
index 000000000000..0eb81fc589d6
--- /dev/null
+++ b/boards/ark/cannode/nuttx-config/include/board_dma_map.h
@@ -0,0 +1,44 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+// DMA1 Channel/Stream Selections
+//--------------------------------------------//---------------------------//----------------
+#define DMACHAN_SPI2_RX DMAMAP_SPI2_RX // DMA1, Stream 3, Channel 0
+#define DMACHAN_SPI2_TX DMAMAP_SPI2_TX // DMA1, Stream 4, Channel 0
+
+// DMA2 Channel/Stream Selections
+//--------------------------------------------//---------------------------//----------------
+#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_2 // DMA2, Stream 2, Channel 3
+#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2 // DMA2, Stream 5, Channel 3
diff --git a/boards/ark/cannode/nuttx-config/nsh/defconfig b/boards/ark/cannode/nuttx-config/nsh/defconfig
new file mode 100644
index 000000000000..5b6364324ee7
--- /dev/null
+++ b/boards/ark/cannode/nuttx-config/nsh/defconfig
@@ -0,0 +1,160 @@
+#
+# This file is autogenerated: PLEASE DO NOT EDIT IT.
+#
+# You can use "make menuconfig" to make any modifications to the installed .config file.
+# You can then do "make savedefconfig" to generate a new defconfig file that includes your
+# modifications.
+#
+# CONFIG_DISABLE_OS_API is not set
+# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
+# CONFIG_NSH_DISABLEBG is not set
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLE_DF is not set
+# CONFIG_NSH_DISABLE_EXEC is not set
+# CONFIG_NSH_DISABLE_EXIT is not set
+# CONFIG_NSH_DISABLE_GET is not set
+# CONFIG_NSH_DISABLE_ITEF is not set
+# CONFIG_NSH_DISABLE_LOOPS is not set
+# CONFIG_NSH_DISABLE_MKFATFS is not set
+# CONFIG_NSH_DISABLE_SEMICOLON is not set
+# CONFIG_NSH_DISABLE_TIME is not set
+# CONFIG_STM32_DMACAPABLE is not set
+CONFIG_ARCH="arm"
+CONFIG_ARCH_BOARD_CUSTOM=y
+CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/cannode/nuttx-config"
+CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
+CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARCH_CHIP_STM32=y
+CONFIG_ARCH_CHIP_STM32F412CE=y
+CONFIG_ARCH_INTERRUPTSTACK=512
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_ARMV7M_MEMCPY=y
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_BOARDCTL_RESET=y
+CONFIG_BOARD_LOOPSPERMSEC=16717
+CONFIG_BOARD_RESET_ON_ASSERT=2
+CONFIG_BUILTIN=y
+CONFIG_C99_BOOL8=y
+CONFIG_CLOCK_MONOTONIC=y
+CONFIG_DEBUG_FULLOPT=y
+CONFIG_DEBUG_HARDFAULT_ALERT=y
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEFAULT_SMALL=y
+CONFIG_DEV_FIFO_SIZE=0
+CONFIG_DEV_PIPE_MAXSIZE=1024
+CONFIG_DEV_PIPE_SIZE=70
+CONFIG_FDCLONE_STDIO=y
+CONFIG_FS_BINFS=y
+CONFIG_FS_CROMFS=y
+CONFIG_FS_FAT=y
+CONFIG_FS_FATTIME=y
+CONFIG_FS_PROCFS=y
+CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
+CONFIG_FS_PROCFS_REGISTER=y
+CONFIG_FS_ROMFS=y
+CONFIG_GRAN=y
+CONFIG_GRAN_INTR=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+CONFIG_I2C=y
+CONFIG_I2C_RESET=y
+CONFIG_IDLETHREAD_STACKSIZE=750
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_LIBC_LONG_LONG=y
+CONFIG_LIBC_STRERROR=y
+CONFIG_MEMSET_64BIT=y
+CONFIG_MEMSET_OPTSPEED=y
+CONFIG_MM_REGIONS=2
+CONFIG_MTD=y
+CONFIG_MTD_BYTE_WRITE=y
+CONFIG_MTD_PARTITION=y
+CONFIG_MTD_RAMTRON=y
+CONFIG_NAME_MAX=40
+CONFIG_NSH_ARCHINIT=y
+CONFIG_NSH_ARGCAT=y
+CONFIG_NSH_BUILTIN_APPS=y
+CONFIG_NSH_CMDPARMS=y
+CONFIG_NSH_CROMFSETC=y
+CONFIG_NSH_DISABLE_IFCONFIG=y
+CONFIG_NSH_DISABLE_IFUPDOWN=y
+CONFIG_NSH_DISABLE_TELNETD=y
+CONFIG_NSH_LINELEN=128
+CONFIG_NSH_MAXARGUMENTS=15
+CONFIG_NSH_NESTDEPTH=8
+CONFIG_NSH_QUOTE=y
+CONFIG_NSH_ROMFSETC=y
+CONFIG_NSH_ROMFSSECTSIZE=128
+CONFIG_NSH_STRERROR=y
+CONFIG_NSH_VARS=y
+CONFIG_PIPES=y
+CONFIG_PREALLOC_TIMERS=50
+CONFIG_PRIORITY_INHERITANCE=y
+CONFIG_PTHREAD_MUTEX_ROBUST=y
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_RAMTRON_SETSPEED=y
+CONFIG_RAM_SIZE=262144
+CONFIG_RAM_START=0x20000000
+CONFIG_RAW_BINARY=y
+CONFIG_RTC_DATETIME=y
+CONFIG_SCHED_ATEXIT=y
+CONFIG_SCHED_HPWORK=y
+CONFIG_SCHED_HPWORKPRIORITY=254
+CONFIG_SCHED_HPWORKSTACKSIZE=3000
+CONFIG_SCHED_INSTRUMENTATION=y
+CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
+CONFIG_SCHED_LPWORK=y
+CONFIG_SCHED_LPWORKPRIORITY=50
+CONFIG_SCHED_LPWORKSTACKSIZE=1632
+CONFIG_SCHED_WAITPID=y
+CONFIG_SEM_PREALLOCHOLDERS=32
+CONFIG_SERIAL_TERMIOS=y
+CONFIG_SIG_DEFAULT=y
+CONFIG_SIG_SIGALRM_ACTION=y
+CONFIG_SIG_SIGUSR1_ACTION=y
+CONFIG_SIG_SIGUSR2_ACTION=y
+CONFIG_SIG_SIGWORK=4
+CONFIG_STACK_COLORATION=y
+CONFIG_START_DAY=30
+CONFIG_START_MONTH=11
+CONFIG_STDIO_BUFFER_SIZE=32
+CONFIG_STM32_ADC1=y
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=y
+CONFIG_STM32_FLASH_CONFIG_G=y
+CONFIG_STM32_FLASH_PREFETCH=y
+CONFIG_STM32_FLOWCONTROL_BROKEN=y
+CONFIG_STM32_I2C1=y
+CONFIG_STM32_JTAG_SW_ENABLE=y
+CONFIG_STM32_PWR=y
+CONFIG_STM32_RTC=y
+CONFIG_STM32_RTC_HSECLOCK=y
+CONFIG_STM32_RTC_MAGIC=0xfacefeee
+CONFIG_STM32_RTC_MAGIC_REG=1
+CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef
+CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
+CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
+CONFIG_STM32_SPI1=y
+CONFIG_STM32_SPI1_DMA=y
+CONFIG_STM32_SPI1_DMA_BUFFER=2048
+CONFIG_STM32_SPI2=y
+CONFIG_STM32_SPI2_DMA=y
+CONFIG_STM32_SPI2_DMA_BUFFER=2048
+CONFIG_STM32_SPI_DMA=y
+CONFIG_STM32_USART1=y
+CONFIG_STM32_USART2=y
+CONFIG_STM32_USART_BREAKS=y
+CONFIG_STM32_WWDG=y
+CONFIG_SYSTEM_NSH=y
+CONFIG_TASK_NAME_SIZE=24
+CONFIG_USART1_BAUD=57600
+CONFIG_USART1_RXBUFSIZE=600
+CONFIG_USART1_TXBUFSIZE=1100
+CONFIG_USART2_BAUD=57600
+CONFIG_USART2_RXBUFSIZE=600
+CONFIG_USART2_SERIAL_CONSOLE=y
+CONFIG_USART2_TXBUFSIZE=1100
+CONFIG_USEC_PER_TICK=1000
+CONFIG_USERMAIN_STACKSIZE=2624
+CONFIG_USER_ENTRYPOINT="nsh_main"
diff --git a/boards/ark/cannode/nuttx-config/scripts/canbootloader_script.ld b/boards/ark/cannode/nuttx-config/scripts/canbootloader_script.ld
new file mode 100644
index 000000000000..cbf9fddc32dc
--- /dev/null
+++ b/boards/ark/cannode/nuttx-config/scripts/canbootloader_script.ld
@@ -0,0 +1,134 @@
+/****************************************************************************
+ * nuttx-config/scripts/canbootloader_script.ld
+ *
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
+ * 256Kb of SRAM. SRAM is split up into three blocks:
+ *
+ * 1) 112Kb of SRAM beginning at address 0x2000:0000
+ * 2) 16Kb of SRAM beginning at address 0x2001:c000
+ * 3) 64Kb of SRAM beginning at address 0x2002:0000
+ * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000
+ *
+ * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
+ * where the code expects to begin execution by jumping to the entry point in
+ * the 0x0800:0000 address range.
+ *
+ * The first 0x10000 of flash is reserved for the bootloader.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08000000, LENGTH = 32K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
+}
+
+OUTPUT_ARCH(arm)
+
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/boards/ark/cannode/nuttx-config/scripts/script.ld b/boards/ark/cannode/nuttx-config/scripts/script.ld
new file mode 100644
index 000000000000..daf33d4b97b0
--- /dev/null
+++ b/boards/ark/cannode/nuttx-config/scripts/script.ld
@@ -0,0 +1,146 @@
+/****************************************************************************
+ * scripts/ld.script
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/* The STM32F412CG has 1Mb of FLASH beginning at address 0x0800:0000 and
+ * 256Kb of SRAM. SRAM is split up into three blocks:
+ *
+ * 1) 112Kb of SRAM beginning at address 0x2000:0000
+ * 2) 16Kb of SRAM beginning at address 0x2001:c000
+ * 3) 64Kb of SRAM beginning at address 0x2002:0000
+ * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000
+ *
+ * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
+ * where the code expects to begin execution by jumping to the entry point in
+ * the 0x0800:0000 address range.
+ *
+ * The first 0x10000 of flash is reserved for the bootloader.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08010000, LENGTH = 928K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
+}
+
+OUTPUT_ARCH(arm)
+
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+EXTERN(_bootdelay_signature)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ . = ALIGN(8);
+ /*
+ * This section positions the app_descriptor_t used
+ * by the make_can_boot_descriptor.py tool to set
+ * the application image's descriptor so that the
+ * uavcan bootloader has the ability to validate the
+ * image crc, size etc
+ */
+ KEEP(*(.app_descriptor))
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/boards/ark/cannode/src/CMakeLists.txt b/boards/ark/cannode/src/CMakeLists.txt
new file mode 100644
index 000000000000..2f1b3015920e
--- /dev/null
+++ b/boards/ark/cannode/src/CMakeLists.txt
@@ -0,0 +1,68 @@
+############################################################################
+#
+# Copyright (c) 2020 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader")
+
+ add_library(drivers_board
+ boot_config.h
+ boot.c
+ led.c
+ led.h
+ )
+ target_link_libraries(drivers_board
+ PRIVATE
+ nuttx_arch
+ nuttx_drivers
+ canbootloader
+ )
+ target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/canbootloader)
+
+else()
+ add_library(drivers_board
+ can.c
+ i2c.cpp
+ init.c
+ led.c
+ spi.cpp
+ timer_config.cpp
+ )
+
+ target_link_libraries(drivers_board
+ PRIVATE
+ arch_spi
+ drivers__led # drv_led_start
+ nuttx_arch
+ nuttx_drivers
+ px4_layer
+ )
+endif()
diff --git a/boards/ark/cannode/src/board_config.h b/boards/ark/cannode/src/board_config.h
new file mode 100644
index 000000000000..bb820a7b66f3
--- /dev/null
+++ b/boards/ark/cannode/src/board_config.h
@@ -0,0 +1,114 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file board_config.h
+ *
+ * board internal definitions
+ */
+
+#pragma once
+
+#include
+#include
+#include
+
+/* CAN Silent mode control */
+#define GPIO_CAN1_SILENT_S0 /* PC14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN14)
+
+/* CAN termination software control */
+#define GPIO_CAN1_TERMINATION /* PC15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN15)
+#define GPIO_CAN_TERM GPIO_CAN1_TERMINATION
+
+/* Boot config */
+#define GPIO_BOOT_CONFIG /* PH1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTH|GPIO_PIN1|GPIO_EXTI)
+
+/* ICM42688p FSYNC */
+#define GPIO_42688P_FSYNC /* PB8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
+
+/* LEDs are driven with open drain to support Anode to 5V or 3.3V */
+#define GPIO_TIM1_CH1 /* PA8 */ (GPIO_TIM1_CH1_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
+#define GPIO_TIM1_CH2 /* PA9 */ (GPIO_TIM1_CH2_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
+#define GPIO_TIM1_CH3 /* PA10 */ (GPIO_TIM1_CH3_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
+
+/* PWM Outputs */
+#define DIRECT_PWM_OUTPUT_CHANNELS 6 // Actually 8
+
+#define GPIO_TIM2_CH1_RESET /* PA0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_TIM2_CH2_RESET /* PA1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_TIM2_CH3_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_TIM3_CH1_RESET /* PB4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN4)
+#define GPIO_TIM3_CH2_RESET /* PB5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_TIM3_CH3_RESET /* PB0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_TIM3_CH4_RESET /* PB1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_TIM4_CH4_RESET /* PB7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN7)
+
+#define GPIO_I2C1_SCL_RESET /* PB6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN6)
+#define GPIO_I2C1_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
+
+#define GPIO_USART1_RX_GPIO /* PB3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3)
+#define GPIO_USART1_TX_GPIO /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15)
+
+#define GPIO_USART2_RX_GPIO /* PA3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_USART2_TX_GPIO /* PA2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN2)
+
+#define FLASH_BASED_PARAMS
+
+/* High-resolution timer */
+#define HRT_TIMER 8 /* use timer 8 for the HRT */
+#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
+
+#define PX4_GPIO_INIT_LIST { \
+ GPIO_CAN1_SILENT_S0, \
+ GPIO_CAN1_TERMINATION, \
+ GPIO_42688P_FSYNC, \
+ GPIO_CAN1_TX, \
+ GPIO_CAN1_RX, \
+ GPIO_I2C1_SCL_RESET, \
+ GPIO_I2C1_SDA_RESET, \
+ }
+
+__BEGIN_DECLS
+
+#define BOARD_HAS_N_S_RGB_LED 1
+#define BOARD_MAX_LEDS BOARD_HAS_N_S_RGB_LED
+
+#ifndef __ASSEMBLY__
+
+extern void stm32_spiinitialize(void);
+
+#include
+
+#endif /* __ASSEMBLY__ */
+
+__END_DECLS
diff --git a/boards/ark/cannode/src/boot.c b/boards/ark/cannode/src/boot.c
new file mode 100644
index 000000000000..a26034e254f6
--- /dev/null
+++ b/boards/ark/cannode/src/boot.c
@@ -0,0 +1,188 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 PX4 Development Team. All rights reserved.
+ * Author: Ben Dyer
+ * Pavel Kirienko
+ * David Sidrane
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include
+#include
+#include "boot_config.h"
+#include "board.h"
+
+#include
+#include
+#include
+
+#include
+#include "led.h"
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the initialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_boardinitialize(void)
+{
+ putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR);
+ stm32_configgpio(GPIO_CAN1_RX);
+ stm32_configgpio(GPIO_CAN1_TX);
+ stm32_configgpio(GPIO_CAN1_SILENT_S0);
+ stm32_configgpio(GPIO_CAN1_TERMINATION);
+ putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
+ putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
+
+#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
+ stm32_configgpio(GPIO_GETNODEINFO_JUMPER);
+#endif
+
+}
+
+/************************************************************************************
+ * Name: board_deinitialize
+ *
+ * Description:
+ * This function is called by the bootloader code prior to booting
+ * the application. Is should place the HW into an benign initialized state.
+ *
+ ************************************************************************************/
+
+void board_deinitialize(void)
+{
+ putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
+}
+
+/****************************************************************************
+ * Name: board_get_product_name
+ *
+ * Description:
+ * Called to retrieve the product name. The returned value is a assumed
+ * to be written to a pascal style string that will be length prefixed
+ * and not null terminated
+ *
+ * Input Parameters:
+ * product_name - A pointer to a buffer to write the name.
+ * maxlen - The maximum number of charter that can be written
+ *
+ * Returned Value:
+ * The length of characters written to the buffer.
+ *
+ ****************************************************************************/
+
+uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen)
+{
+ DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME));
+ memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME));
+ return UAVCAN_STRLEN(HW_UAVCAN_NAME);
+}
+
+/****************************************************************************
+ * Name: board_get_hardware_version
+ *
+ * Description:
+ * Called to retrieve the hardware version information. The function
+ * will first initialize the the callers struct to all zeros.
+ *
+ * Input Parameters:
+ * hw_version - A pointer to a uavcan_hardwareversion_t.
+ *
+ * Returned Value:
+ * Length of the unique_id
+ *
+ ****************************************************************************/
+
+size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version)
+{
+ memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t));
+
+ hw_version->major = HW_VERSION_MAJOR;
+ hw_version->minor = HW_VERSION_MINOR;
+
+ return board_get_mfguid(*(mfguid_t *) hw_version->unique_id);
+}
+
+/****************************************************************************
+ * Name: board_indicate
+ *
+ * Description:
+ * Provides User feedback to indicate the state of the bootloader
+ * on board specific hardware.
+ *
+ * Input Parameters:
+ * indication - A member of the uiindication_t
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)}
+
+typedef begin_packed_struct struct led_t {
+ uint8_t red;
+ uint8_t green;
+ uint8_t blue;
+ uint8_t hz;
+} end_packed_struct led_t;
+
+static const led_t i2l[] = {
+
+ led(0, off, 0, 0, 0, 0),
+ led(1, reset, 128, 128, 128, 30),
+ led(2, autobaud_start, 0, 128, 0, 1),
+ led(3, autobaud_end, 0, 128, 0, 2),
+ led(4, allocation_start, 0, 0, 64, 2),
+ led(5, allocation_end, 0, 128, 64, 3),
+ led(6, fw_update_start, 32, 128, 64, 3),
+ led(7, fw_update_erase_fail, 32, 128, 32, 3),
+ led(8, fw_update_invalid_response, 64, 0, 0, 1),
+ led(9, fw_update_timeout, 64, 0, 0, 2),
+ led(a, fw_update_invalid_crc, 64, 0, 0, 4),
+ led(b, jump_to_app, 0, 128, 0, 10),
+
+};
+
+void board_indicate(uiindication_t indication)
+{
+ rgb_led(i2l[indication].red,
+ i2l[indication].green,
+ i2l[indication].blue,
+ i2l[indication].hz);
+}
diff --git a/boards/ark/cannode/src/boot_config.h b/boards/ark/cannode/src/boot_config.h
new file mode 100644
index 000000000000..eab3c76c6c13
--- /dev/null
+++ b/boards/ark/cannode/src/boot_config.h
@@ -0,0 +1,130 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 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 boot_config.h
+ *
+ * bootloader definitions that configures the behavior and options
+ * of the Boot loader
+ * This file is relies on the parent folder's boot_config.h file and defines
+ * different usages of the hardware for bootloading
+ */
+
+#pragma once
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+/* Bring in the board_config.h definitions
+ * todo:make this be pulled in from a targed's build
+ * files in nuttx*/
+
+#include "board_config.h"
+#include "uavcan.h"
+#include
+
+#include
+
+#include
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
+
+//todo:wrap OPT_x in in ifdefs for command line definitions
+#define OPT_TBOOT_MS 5000
+#define OPT_NODE_STATUS_RATE_MS 800
+#define OPT_NODE_INFO_RATE_MS 50
+#define OPT_BL_NUMBER_TIMERS 7
+
+/*
+ * This Option set is set to 1 ensure a provider of firmware has an
+ * opportunity update the node's firmware.
+ * This Option is the default policy and can be overridden by
+ * a jumper
+ * When this Policy is set, the node will ignore tboot and
+ * wait indefinitely for a GetNodeInfo request before booting.
+ *
+ * OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow
+ * the polarity of the jumper to be True Active
+ *
+ * wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
+ * Jumper
+ * yes 1 0 x
+ * yes 1 1 Active
+ * no 1 1 Not Active
+ * no 0 0 X
+ * yes 0 1 Active
+ * no 0 1 Not Active
+ *
+ */
+#define OPT_WAIT_FOR_GETNODEINFO 0
+#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1
+#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0
+
+#define OPT_ENABLE_WD 1
+
+#define OPT_RESTART_TIMEOUT_MS 20000
+
+/* Reserved for the Booloader */
+#define OPT_BOOTLOADER_SIZE_IN_K (1024*64)
+
+/* Reserved for the application out of the total
+ * system flash minus the BOOTLOADER_SIZE_IN_K
+ */
+#define OPT_APPLICATION_RESERVER_IN_K 0
+
+#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K
+#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K))
+
+
+#define FLASH_BASE STM32_FLASH_BASE
+#define FLASH_SIZE STM32_FLASH_SIZE
+
+#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET)
+#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET)
+#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t)))
+#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t)))
+#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t)))
+
+/* If this board uses big flash that have large sectors */
+
+#define OPT_USE_YIELD
+
+/* Bootloader Option*****************************************************************
+ *
+ */
+#define GPIO_GETNODEINFO_JUMPER (GPIO_BOOT_CONFIG & ~GPIO_EXTI)
diff --git a/boards/ark/cannode/src/can.c b/boards/ark/cannode/src/can.c
new file mode 100644
index 000000000000..acc20252fab0
--- /dev/null
+++ b/boards/ark/cannode/src/can.c
@@ -0,0 +1,130 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2021 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 can.c
+ *
+ * Board-specific CAN functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include
+
+#include
+#include
+
+#include
+#include
+
+#include "chip.h"
+#include "arm_arch.h"
+
+#include "stm32.h"
+#include "stm32_can.h"
+#include "board_config.h"
+
+#ifdef CONFIG_CAN
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
+# undef CONFIG_STM32_CAN2
+#endif
+
+#ifdef CONFIG_STM32_CAN1
+# define CAN_PORT 1
+#else
+# define CAN_PORT 2
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+int can_devinit(void);
+
+/************************************************************************************
+ * Name: can_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/can.
+ *
+ ************************************************************************************/
+
+int can_devinit(void)
+{
+ static bool initialized = false;
+ struct can_dev_s *can;
+ int ret;
+
+ /* Check if we have already initialized */
+
+ if (!initialized) {
+ /* Call stm32_caninitialize() to get an instance of the CAN interface */
+
+ can = stm32_caninitialize(CAN_PORT);
+
+ if (can == NULL) {
+ canerr("ERROR: Failed to get CAN interface\n");
+ return -ENODEV;
+ }
+
+ /* Register the CAN driver at "/dev/can0" */
+
+ ret = can_register("/dev/can0", can);
+
+ if (ret < 0) {
+ canerr("ERROR: can_register failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif
diff --git a/boards/ark/can-flow/src/i2c.cpp b/boards/ark/cannode/src/i2c.cpp
similarity index 100%
rename from boards/ark/can-flow/src/i2c.cpp
rename to boards/ark/cannode/src/i2c.cpp
diff --git a/boards/ark/cannode/src/init.c b/boards/ark/cannode/src/init.c
new file mode 100644
index 000000000000..491bc348b402
--- /dev/null
+++ b/boards/ark/cannode/src/init.c
@@ -0,0 +1,188 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 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 init.c
+ *
+ * board specific early startup code. This file implements the
+ * board_app_initialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialization.
+ */
+
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+
+#include
+#include "board_config.h"
+#include "led.h"
+#include
+
+#include
+
+#include
+#include
+#include
+
+#include
+
+#include
+#include
+
+#include
+#include
+
+# if defined(FLASH_BASED_PARAMS)
+# include
+#endif
+
+/************************************************************************************
+ * Name: board_on_reset
+ *
+ * Description:
+ * Optionally provided function called on entry to board_system_reset
+ * It should perform any house keeping prior to the rest.
+ *
+ * status - 1 if resetting to boot loader
+ * 0 if just resetting
+ *
+ ************************************************************************************/
+__EXPORT void board_on_reset(int status)
+{
+ // Configure the GPIO pins to outputs and keep them low.
+ for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
+ px4_arch_configgpio(io_timer_channel_get_gpio_output(i));
+ }
+
+ /*
+ * On resets invoked from system (not boot) insure we establish a low
+ * output state (discharge the pins) on PWM pins before they become inputs.
+ */
+
+ if (status >= 0) {
+ up_mdelay(400);
+ }
+}
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the initialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_boardinitialize(void)
+{
+ // Reset all PWM to Low outputs.
+ board_on_reset(-1);
+
+ watchdog_init();
+
+ /* configure pins */
+ const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
+ px4_gpio_init(gpio, arraySize(gpio));
+
+ // Configure SPI all interfaces GPIO & enable power.
+ stm32_spiinitialize();
+}
+
+/****************************************************************************
+ * Name: board_app_initialize
+ *
+ * Description:
+ * Perform application specific initialization. This function is never
+ * called directly from application code, but only indirectly via the
+ * (non-standard) boardctl() interface using the command BOARDIOC_INIT.
+ *
+ * Input Parameters:
+ * arg - The boardctl() argument is passed to the board_app_initialize()
+ * implementation without modification. The argument has no
+ * meaning to NuttX; the meaning of the argument is a contract
+ * between the board-specific initalization logic and the the
+ * matching application logic. The value cold be such things as a
+ * mode enumeration value, a set of DIP switch switch settings, a
+ * pointer to configuration data read from a file or serial FLASH,
+ * or whatever you would like to do with it. Every implementation
+ * should accept zero/NULL as a default configuration.
+ *
+ * Returned Value:
+ * Zero (OK) is returned on success; a negated errno value is returned on
+ * any failure to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+__EXPORT int board_app_initialize(uintptr_t arg)
+{
+ px4_platform_init();
+
+#if defined(SERIAL_HAVE_RXDMA)
+ // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
+ static struct hrt_call serial_dma_call;
+ hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
+#endif
+
+#if defined(FLASH_BASED_PARAMS)
+ static sector_descriptor_t params_sector_map[] = {
+ {2, 16 * 1024, 0x08008000},
+ {3, 16 * 1024, 0x0800C000},
+ {0, 0, 0},
+ };
+
+ /* Initialize the flashfs layer to use heap allocated memory */
+ int result = parameter_flashfs_init(params_sector_map, NULL, 0);
+
+ if (result != OK) {
+ syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
+ }
+
+#endif // FLASH_BASED_PARAMS
+
+ /* Configure the HW based on the manifest */
+
+ px4_platform_configure();
+
+ return OK;
+}
diff --git a/boards/ark/cannode/src/led.c b/boards/ark/cannode/src/led.c
new file mode 100644
index 000000000000..9a80cae08923
--- /dev/null
+++ b/boards/ark/cannode/src/led.c
@@ -0,0 +1,124 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 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 led.c
+ *
+ * LED backend.
+ */
+
+#include
+
+#include
+
+#include "chip.h"
+#include "stm32_gpio.h"
+#include "board_config.h"
+
+#include
+#include
+
+#include "led.h"
+
+#define TMR_BASE STM32_TIM1_BASE
+#define TMR_FREQUENCY STM32_APB2_TIM1_CLKIN
+#define TMR_REG(o) (TMR_BASE+(o))
+
+void rgb_led(int r, int g, int b, int freqs)
+{
+
+ long fosc = TMR_FREQUENCY;
+ long prescale = 2048;
+ long p1s = fosc / prescale;
+ long p0p5s = p1s / 2;
+ uint16_t val;
+ static bool once = 0;
+
+ if (!once) {
+ once = 1;
+
+ /* Enabel Clock to Block */
+ modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN);
+
+ /* Reload */
+
+ val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET));
+ val |= ATIM_EGR_UG;
+ putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET));
+
+ /* Set Prescaler STM32_TIM_SETCLOCK */
+
+ putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET));
+
+ /* Enable STM32_TIM_SETMODE*/
+
+ putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET));
+
+
+ putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) | ATIM_CCMR1_OC1PE |
+ (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET));
+ putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET));
+ putreg16(ATIM_CCER_CC3E | ATIM_CCER_CC3P |
+ ATIM_CCER_CC2E | ATIM_CCER_CC2P |
+ ATIM_CCER_CC1E | ATIM_CCER_CC1P, TMR_REG(STM32_GTIM_CCER_OFFSET));
+
+
+ stm32_configgpio(GPIO_TIM1_CH1);
+ stm32_configgpio(GPIO_TIM1_CH2);
+ stm32_configgpio(GPIO_TIM1_CH3);
+
+ /* master output enable = on */
+ putreg16(ATIM_BDTR_MOE, (TMR_REG(STM32_ATIM_BDTR_OFFSET)));
+ }
+
+ long p = freqs == 0 ? p1s : p1s / freqs;
+ putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET));
+
+ p = freqs == 0 ? p1s + 1 : p0p5s / freqs;
+
+ putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR1_OFFSET));
+ putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET));
+ putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET));
+
+ val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET));
+
+ if (freqs == 0) {
+ val &= ~ATIM_CR1_CEN;
+
+ } else {
+ val |= ATIM_CR1_CEN;
+ }
+
+ putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET));
+
+}
diff --git a/boards/ark/cannode/src/led.h b/boards/ark/cannode/src/led.h
new file mode 100644
index 000000000000..b68e4aa70d0c
--- /dev/null
+++ b/boards/ark/cannode/src/led.h
@@ -0,0 +1,37 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2015 PX4 Development Team. All rights reserved.
+ * Author: David Sidrane
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+__BEGIN_DECLS
+void rgb_led(int r, int g, int b, int freqs);
+__END_DECLS
diff --git a/boards/ark/cannode/src/spi.cpp b/boards/ark/cannode/src/spi.cpp
new file mode 100644
index 000000000000..ab7d82a3d831
--- /dev/null
+++ b/boards/ark/cannode/src/spi.cpp
@@ -0,0 +1,48 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2021 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#include
+#include
+#include
+
+constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
+ initSPIBus(SPI::Bus::SPI1, {
+ initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortA, GPIO::Pin4}, SPI::DRDY{GPIO::PortB, GPIO::Pin2}),
+ }),
+ initSPIBusExternal(SPI::Bus::SPI2, {
+ initSPIConfigExternal(SPI::CS{GPIO::PortB, GPIO::Pin12}),
+ initSPIConfigExternal(SPI::CS{GPIO::PortC, GPIO::Pin13}),
+ }),
+};
+
+static constexpr bool unused = validateSPIConfig(px4_spi_buses);
diff --git a/boards/ark/cannode/src/timer_config.cpp b/boards/ark/cannode/src/timer_config.cpp
new file mode 100644
index 000000000000..bc69d4b7ea1b
--- /dev/null
+++ b/boards/ark/cannode/src/timer_config.cpp
@@ -0,0 +1,54 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#include
+
+constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
+ initIOTimer(Timer::Timer2),
+ initIOTimer(Timer::Timer3),
+ //initIOTimer(Timer::Timer4),
+};
+
+constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
+ initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}),
+ initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}),
+ initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel3}, {GPIO::PortB, GPIO::Pin10}),
+ initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel1}, {GPIO::PortB, GPIO::Pin4}),
+ initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel2}, {GPIO::PortB, GPIO::Pin5}),
+ initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}),
+ //initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}),
+ //initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortB, GPIO::Pin7}),
+};
+
+constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
+ initIOTimerChannelMapping(io_timers, timer_io_channels);
diff --git a/boards/ark/cannode/uavcan_board_identity b/boards/ark/cannode/uavcan_board_identity
new file mode 100644
index 000000000000..44ea18cc7d39
--- /dev/null
+++ b/boards/ark/cannode/uavcan_board_identity
@@ -0,0 +1,17 @@
+# UAVCAN boot loadable Module ID
+set(uavcanblid_sw_version_major 0)
+set(uavcanblid_sw_version_minor 1)
+add_definitions(
+ -DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major}
+ -DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor}
+)
+
+set(uavcanblid_hw_version_major 0)
+set(uavcanblid_hw_version_minor 83)
+set(uavcanblid_name "\"org.ark.cannode\"")
+
+add_definitions(
+ -DHW_UAVCAN_NAME=${uavcanblid_name}
+ -DHW_VERSION_MAJOR=${uavcanblid_hw_version_major}
+ -DHW_VERSION_MINOR=${uavcanblid_hw_version_minor}
+)
diff --git a/boards/atl/mantis-edu/cmake/upload.cmake b/boards/atl/mantis-edu/cmake/upload.cmake
new file mode 100644
index 000000000000..b85bacd27957
--- /dev/null
+++ b/boards/atl/mantis-edu/cmake/upload.cmake
@@ -0,0 +1,46 @@
+############################################################################
+#
+# Copyright (c) 2021 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.
+#
+############################################################################
+
+
+set(PX4_FW_NAME ${PX4_BINARY_DIR}/${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_${PX4_BOARD_LABEL}.px4)
+
+# The file needs to have that name in order to be updated automatically.
+set(UPLOAD_NAME autopilot.px4)
+
+add_custom_target(upload_wifi
+ COMMAND ${CMAKE_COMMAND} -E copy ${PX4_FW_NAME} ${UPLOAD_NAME}
+ COMMAND ${PX4_SOURCE_DIR}/boards/atl/mantis-edu/upload.sh ${UPLOAD_NAME}
+ DEPENDS ${PX4_FW_NAME}
+ COMMENT "uploading autopilot.px4 file"
+ USES_TERMINAL
+)
diff --git a/boards/atl/mantis-edu/default.px4board b/boards/atl/mantis-edu/default.px4board
new file mode 100644
index 000000000000..4116386115f3
--- /dev/null
+++ b/boards/atl/mantis-edu/default.px4board
@@ -0,0 +1,53 @@
+CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
+CONFIG_BOARD_ARCHITECTURE="cortex-m7"
+CONFIG_DRIVERS_ADC_BOARD_ADC=y
+CONFIG_DRIVERS_GPS=y
+CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
+CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
+CONFIG_DRIVERS_BAROMETER_MAIERTEK_MPC2520=y
+CONFIG_DRIVERS_TAP_ESC=y
+CONFIG_MODULES_BATTERY_STATUS=y
+CONFIG_MODULES_CAMERA_FEEDBACK=y
+CONFIG_MODULES_COMMANDER=y
+CONFIG_MODULES_DATAMAN=y
+CONFIG_MODULES_EKF2=y
+CONFIG_MODULES_EVENTS=y
+CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
+CONFIG_MODULES_GYRO_CALIBRATION=y
+CONFIG_MODULES_GYRO_FFT=y
+CONFIG_MODULES_LAND_DETECTOR=y
+CONFIG_MODULES_LOAD_MON=y
+CONFIG_MODULES_LOGGER=y
+CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
+CONFIG_MODULES_MANUAL_CONTROL=y
+CONFIG_MODULES_MAVLINK=y
+CONFIG_MODULES_MC_ATT_CONTROL=y
+CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
+CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
+CONFIG_MODULES_MC_POS_CONTROL=y
+CONFIG_MODULES_MC_RATE_CONTROL=y
+CONFIG_MODULES_CONTROL_ALLOCATOR=y
+CONFIG_MODULES_NAVIGATOR=y
+CONFIG_MODULES_RC_UPDATE=y
+CONFIG_MODULES_SENSORS=y
+CONFIG_MODULES_SIH=y
+CONFIG_MODULES_GIMBAL=y
+CONFIG_SYSTEMCMDS_BL_UPDATE=y
+CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
+CONFIG_SYSTEMCMDS_DMESG=y
+CONFIG_SYSTEMCMDS_DUMPFILE=y
+CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
+CONFIG_SYSTEMCMDS_LED_CONTROL=y
+CONFIG_SYSTEMCMDS_MIXER=y
+CONFIG_SYSTEMCMDS_MOTOR_TEST=y
+CONFIG_SYSTEMCMDS_PARAM=y
+CONFIG_SYSTEMCMDS_PERF=y
+CONFIG_SYSTEMCMDS_REBOOT=y
+CONFIG_SYSTEMCMDS_SHUTDOWN=y
+CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
+CONFIG_SYSTEMCMDS_TOP=y
+CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
+CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
+CONFIG_SYSTEMCMDS_UORB=y
+CONFIG_SYSTEMCMDS_VER=y
+CONFIG_SYSTEMCMDS_WORK_QUEUE=y
diff --git a/boards/atl/mantis-edu/extras/atl_mantis-edu_bootloader.bin b/boards/atl/mantis-edu/extras/atl_mantis-edu_bootloader.bin
new file mode 100755
index 000000000000..554ae898cecd
Binary files /dev/null and b/boards/atl/mantis-edu/extras/atl_mantis-edu_bootloader.bin differ
diff --git a/boards/atl/mantis-edu/firmware.prototype b/boards/atl/mantis-edu/firmware.prototype
new file mode 100644
index 000000000000..5c37f437d787
--- /dev/null
+++ b/boards/atl/mantis-edu/firmware.prototype
@@ -0,0 +1,13 @@
+{
+ "board_id": 97,
+ "magic": "PX4FWv1",
+ "description": "Firmware for the Advanced Technology Labs (ATL) Mantis EDU (V18S) board",
+ "image": "",
+ "build_time": 0,
+ "summary": "atl_mantis-edu",
+ "version": "0.1",
+ "image_size": 0,
+ "image_maxsize": 2064384,
+ "git_identity": "",
+ "board_revision": 0
+}
diff --git a/boards/atl/mantis-edu/init/rc.board_defaults b/boards/atl/mantis-edu/init/rc.board_defaults
new file mode 100644
index 000000000000..01c211c03e6f
--- /dev/null
+++ b/boards/atl/mantis-edu/init/rc.board_defaults
@@ -0,0 +1,24 @@
+#!/bin/sh
+#
+# board specific defaults
+#------------------------------------------------------------------------------
+
+param set-default SYS_AUTOSTART 4061
+
+param set-default BAT1_V_DIV 9.0
+
+param set-default COM_ARM_SDCARD 0
+
+param set-default SENS_EXT_I2C_PRB 0
+
+param set-default EKF2_MULTI_IMU 1
+param set-default EKF2_MULTI_MAG 1
+param set-default SENS_IMU_MODE 0
+param set-default SENS_MAG_MODE 0
+
+param set-default EV_TSK_STAT_DIS 1
+
+param set-default SYS_DM_BACKEND 1
+
+# Use MAVLink log streaming
+set LOGGER_ARGS "-m mavlink -c 0.5"
diff --git a/boards/atl/mantis-edu/init/rc.board_extras b/boards/atl/mantis-edu/init/rc.board_extras
new file mode 100644
index 000000000000..e3969b7473d9
--- /dev/null
+++ b/boards/atl/mantis-edu/init/rc.board_extras
@@ -0,0 +1,5 @@
+#!/bin/sh
+
+tap_esc start -d /dev/ttyS4 -n 4
+sleep 1
+mixer load /dev/tap_esc /etc/mixers/quad_x.main.mix
diff --git a/boards/atl/mantis-edu/init/rc.board_mavlink b/boards/atl/mantis-edu/init/rc.board_mavlink
new file mode 100644
index 000000000000..c8bc7b224acb
--- /dev/null
+++ b/boards/atl/mantis-edu/init/rc.board_mavlink
@@ -0,0 +1,16 @@
+#!/bin/sh
+#
+# board specific MAVLink startup script.
+#------------------------------------------------------------------------------
+
+set GIMBAL_TTY /dev/ttyS3
+set MAV_RATE 40000
+set BAUDRATE 500000
+
+mavlink start -r ${MAV_RATE} -d ${GIMBAL_TTY} -b ${BAUDRATE}
+mavlink stream -d ${GIMBAL_TTY} -s SYSTEM_TIME -r 0.5
+mavlink stream -d ${GIMBAL_TTY} -s AUTOPILOT_STATE_FOR_GIMBAL_DEVICE -r 20
+mavlink stream -d ${GIMBAL_TTY} -s GIMBAL_DEVICE_SET_ATTITUDE -r 20
+
+# optical flow
+mavlink start -d /dev/ttyS2 -m custom -b 500000
diff --git a/boards/atl/mantis-edu/init/rc.board_sensors b/boards/atl/mantis-edu/init/rc.board_sensors
new file mode 100644
index 000000000000..6c07fa135319
--- /dev/null
+++ b/boards/atl/mantis-edu/init/rc.board_sensors
@@ -0,0 +1,17 @@
+#!/bin/sh
+#
+# board specific sensors init
+#------------------------------------------------------------------------------
+
+board_adc start
+
+# SPI1 icm20602 IMU
+icm20602 start -s -b 1 -R 8
+
+# I2C2 ist8310 magnetometer
+ist8310 start -I -b 2 -R 14
+
+# I2C4 mpc2520 barometer
+mpc2520 start -I -b 4
+
+gps start -d /dev/ttyS0 -p ubx
diff --git a/boards/atl/mantis-edu/nuttx-config/include/board.h b/boards/atl/mantis-edu/nuttx-config/include/board.h
new file mode 100644
index 000000000000..291c3e7e46e1
--- /dev/null
+++ b/boards/atl/mantis-edu/nuttx-config/include/board.h
@@ -0,0 +1,332 @@
+/************************************************************************************
+ * nuttx-configs/px4_fmu-v5/include/board.h
+ *
+ * Copyright (C) 2016-2018 Gregory Nutt. All rights reserved.
+ * Authors: David Sidrane
+ *
+ * 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 NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+#ifndef __NUTTX_CONFIG_PX4_FMU_V5_INCLUDE_BOARD_H
+#define __NUTTX_CONFIG_PX4_FMU_V5_INCLUDE_BOARD_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+#include "board_dma_map.h"
+
+#include
+
+#ifndef __ASSEMBLY__
+# include
+#endif
+
+#include "stm32_rcc.h"
+#include "stm32_sdmmc.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Clocking *************************************************************************/
+/* The px4_fmu-v5 board provides the following clock sources:
+ *
+ * X301: 16 MHz crystal for HSE
+ *
+ * So we have these clock source available within the STM32
+ *
+ * HSI: 16 MHz RC factory-trimmed
+ * HSE: 16 MHz crystal for HSE
+ */
+
+#define STM32_BOARD_XTAL 16000000ul
+
+#define STM32_HSI_FREQUENCY 16000000ul
+#define STM32_LSI_FREQUENCY 32000
+#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
+#define STM32_LSE_FREQUENCY 0
+
+/* Main PLL Configuration.
+ *
+ * PLL source is HSE = 16,000,000
+ *
+ * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
+ * Subject to:
+ *
+ * 2 <= PLLM <= 63
+ * 192 <= PLLN <= 432
+ * 192 MHz <= PLL_VCO <= 432MHz
+ *
+ * SYSCLK = PLL_VCO / PLLP
+ * Subject to
+ *
+ * PLLP = {2, 4, 6, 8}
+ * SYSCLK <= 216 MHz
+ *
+ * USB OTG FS, SDMMC and RNG Clock = PLL_VCO / PLLQ
+ * Subject to
+ * The USB OTG FS requires a 48 MHz clock to work correctly. The SDMMC
+ * and the random number generator need a frequency lower than or equal
+ * to 48 MHz to work correctly.
+ *
+ * 2 <= PLLQ <= 15
+ */
+
+/* Highest SYSCLK with USB OTG FS clock = 48 MHz
+ *
+ * PLL_VCO = (16,000,000 / 8) * 216 = 432 MHz
+ * SYSCLK = 432 MHz / 2 = 216 MHz
+ * USB OTG FS, SDMMC and RNG Clock = 432 MHz / 9 = 48 MHz
+ */
+#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8)
+#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(216)
+#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
+#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(9)
+
+#define STM32_VCO_FREQUENCY ((STM32_HSE_FREQUENCY / 8) * 216)
+#define STM32_SYSCLK_FREQUENCY (STM32_VCO_FREQUENCY / 2)
+#define STM32_OTGFS_FREQUENCY (STM32_VCO_FREQUENCY / 9)
+
+/* Configure factors for PLLSAI clock */
+#define CONFIG_STM32F7_PLLSAI 1
+#define STM32_RCC_PLLSAICFGR_PLLSAIN RCC_PLLSAICFGR_PLLSAIN(192)
+#define STM32_RCC_PLLSAICFGR_PLLSAIP RCC_PLLSAICFGR_PLLSAIP(8)
+#define STM32_RCC_PLLSAICFGR_PLLSAIQ RCC_PLLSAICFGR_PLLSAIQ(4)
+#define STM32_RCC_PLLSAICFGR_PLLSAIR RCC_PLLSAICFGR_PLLSAIR(2)
+
+/* Configure Dedicated Clock Configuration Register */
+#define STM32_RCC_DCKCFGR1_PLLI2SDIVQ RCC_DCKCFGR1_PLLI2SDIVQ(1)
+#define STM32_RCC_DCKCFGR1_PLLSAIDIVQ RCC_DCKCFGR1_PLLSAIDIVQ(1)
+#define STM32_RCC_DCKCFGR1_PLLSAIDIVR RCC_DCKCFGR1_PLLSAIDIVR(0)
+#define STM32_RCC_DCKCFGR1_SAI1SRC RCC_DCKCFGR1_SAI1SEL(0)
+#define STM32_RCC_DCKCFGR1_SAI2SRC RCC_DCKCFGR1_SAI2SEL(0)
+#define STM32_RCC_DCKCFGR1_TIMPRESRC 0
+#define STM32_RCC_DCKCFGR1_DFSDM1SRC 0
+#define STM32_RCC_DCKCFGR1_ADFSDM1SRC 0
+
+
+/* Configure factors for PLLI2S clock */
+#define CONFIG_STM32F7_PLLI2S 1
+#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SP RCC_PLLI2SCFGR_PLLI2SP(2)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2)
+#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2)
+
+/* Configure Dedicated Clock Configuration Register 2 */
+#define STM32_RCC_DCKCFGR2_USART1SRC RCC_DCKCFGR2_USART1SEL_APB
+#define STM32_RCC_DCKCFGR2_USART2SRC RCC_DCKCFGR2_USART2SEL_APB
+#define STM32_RCC_DCKCFGR2_UART4SRC RCC_DCKCFGR2_UART4SEL_APB
+#define STM32_RCC_DCKCFGR2_UART5SRC RCC_DCKCFGR2_UART5SEL_APB
+#define STM32_RCC_DCKCFGR2_USART6SRC RCC_DCKCFGR2_USART6SEL_APB
+#define STM32_RCC_DCKCFGR2_UART7SRC RCC_DCKCFGR2_UART7SEL_APB
+#define STM32_RCC_DCKCFGR2_UART8SRC RCC_DCKCFGR2_UART8SEL_APB
+#define STM32_RCC_DCKCFGR2_I2C1SRC RCC_DCKCFGR2_I2C1SEL_HSI
+#define STM32_RCC_DCKCFGR2_I2C2SRC RCC_DCKCFGR2_I2C2SEL_HSI
+#define STM32_RCC_DCKCFGR2_I2C3SRC RCC_DCKCFGR2_I2C3SEL_HSI
+#define STM32_RCC_DCKCFGR2_I2C4SRC RCC_DCKCFGR2_I2C4SEL_HSI
+#define STM32_RCC_DCKCFGR2_LPTIM1SRC RCC_DCKCFGR2_LPTIM1SEL_APB
+#define STM32_RCC_DCKCFGR2_CECSRC RCC_DCKCFGR2_CECSEL_HSI
+#define STM32_RCC_DCKCFGR2_CK48MSRC RCC_DCKCFGR2_CK48MSEL_PLL
+#define STM32_RCC_DCKCFGR2_SDMMCSRC RCC_DCKCFGR2_SDMMCSEL_48MHZ
+#define STM32_RCC_DCKCFGR2_SDMMC2SRC RCC_DCKCFGR2_SDMMC2SEL_48MHZ
+#define STM32_RCC_DCKCFGR2_DSISRC RCC_DCKCFGR2_DSISEL_PHY
+
+
+/* Several prescalers allow the configuration of the two AHB buses, the
+ * high-speed APB (APB2) and the low-speed APB (APB1) domains. The maximum
+ * frequency of the two AHB buses is 216 MHz while the maximum frequency of
+ * the high-speed APB domains is 108 MHz. The maximum allowed frequency of
+ * the low-speed APB domain is 54 MHz.
+ */
+
+/* AHB clock (HCLK) is SYSCLK (216 MHz) */
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
+#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
+
+/* APB1 clock (PCLK1) is HCLK/4 (54 MHz) */
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4)
+
+/* Timers driven from APB1 will be twice PCLK1 */
+#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
+
+/* APB2 clock (PCLK2) is HCLK/2 (108MHz) */
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
+#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
+
+/* Timers driven from APB2 will be twice PCLK2 */
+#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY)
+
+/* SDMMC dividers. Note that slower clocking is required when DMA is disabled
+ * in order to avoid RX overrun/TX underrun errors due to delayed responses
+ * to service FIFOs in interrupt driven mode. These values have not been
+ * tuned!!!
+ *
+ * SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(118+2)=400 KHz
+ */
+
+/* Use the Falling edge of the SDIO_CLK clock to change the edge the
+ * data and commands are change on
+ */
+
+#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
+
+#define STM32_SDMMC_INIT_CLKDIV (118 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
+
+/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz
+ * DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz
+ */
+
+#ifdef CONFIG_STM32F7_SDMMC_DMA
+# define STM32_SDMMC_MMCXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
+#else
+# define STM32_SDMMC_MMCXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
+#endif
+
+/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz
+ * DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz
+ */
+//TODO #warning "Check Freq for 24mHz"
+
+#ifdef CONFIG_STM32F7_SDMMC_DMA
+# define STM32_SDMMC_SDXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
+#else
+# define STM32_SDMMC_SDXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
+#endif
+
+/* FLASH wait states
+ *
+ * --------- ---------- -----------
+ * VDD MAX SYSCLK WAIT STATES
+ * --------- ---------- -----------
+ * 1.7-2.1 V 180 MHz 8
+ * 2.1-2.4 V 216 MHz 9
+ * 2.4-2.7 V 216 MHz 8
+ * 2.7-3.6 V 216 MHz 7
+ * --------- ---------- -----------
+ */
+
+#define BOARD_FLASH_WAITSTATES 7
+
+/* LED index values for use with board_userled() */
+
+#define BOARD_LED1 0
+#define BOARD_LED2 1
+#define BOARD_LED3 2
+#define BOARD_NLEDS 3
+
+#define BOARD_LED_RED BOARD_LED1
+#define BOARD_LED_GREEN BOARD_LED2
+#define BOARD_LED_BLUE BOARD_LED3
+
+/* Thus if the Green LED is statically on, NuttX has successfully booted and
+ * is, apparently, running normally. If the Red LED is flashing at
+ * approximately 2Hz, then a fatal error has been detected and the system
+ * has halted.
+ */
+
+/* Alternate function pin selections ************************************************/
+
+#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PB7 */
+#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PB6 */
+
+#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
+#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
+#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
+#define GPIO_USART2_CTS GPIO_USART2_CTS_2 /* PD3 */
+
+#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
+#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
+#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
+#define GPIO_USART3_CTS GPIO_USART3_CTS_2 /* PD11 */
+
+#define GPIO_UART4_RX GPIO_UART4_RX_4 /* PD0 */
+#define GPIO_UART4_TX GPIO_UART4_TX_4 /* PD1 */
+
+#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PB12 */
+#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PB13 */
+
+#define GPIO_USART6_RX GPIO_USART6_RX_2 /* PG9 */
+#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14 */
+#define GPIO_USART6_RTS GPIO_USART6_RTS_2 /* PG8 */
+#define GPIO_USART6_CTS GPIO_USART6_CTS_2 /* PG15 */
+
+#define GPIO_UART7_RX GPIO_UART7_RX_2 /* PF6 */
+#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8 */
+
+/* USART8: has no remap
+ *
+ * GPIO_UART8_RX PE0[CN12-64]
+ * GPIO_UART8_TX PE1[CN11-61]
+ */
+
+
+/* SPI */
+#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
+#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
+#define GPIO_SPI1_SCK GPIO_SPI1_SCK_3 /* PG11 */
+
+#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE13 */
+#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE6 */
+#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 /* PE2 */
+
+
+/* I2C */
+#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */
+#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */
+
+#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
+#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */
+
+/* SDMMC1
+ *
+ * VDD 3.3
+ * GND
+ * SDMMC1_CK PC12
+ * SDMMC1_CMD PD2
+ * SDMMC1_D0 PC8
+ * SDMMC1_D1 PC9
+ * SDMMC1_D2 PC10
+ * SDMMC1_D3 PC11
+ * GPIO_SDMMC1_NCD PG0
+ */
+
+#endif /*__NUTTX_CONFIG_PX4_FMU_V5_INCLUDE_BOARD_H */
diff --git a/boards/atl/mantis-edu/nuttx-config/include/board_dma_map.h b/boards/atl/mantis-edu/nuttx-config/include/board_dma_map.h
new file mode 100644
index 000000000000..2a017ed8c618
--- /dev/null
+++ b/boards/atl/mantis-edu/nuttx-config/include/board_dma_map.h
@@ -0,0 +1,99 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2020 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+/*
+| DMA1 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 |
+|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|
+| Channel 0 | SPI3_RX_1 | SPDIFRX_DT | SPI3_RX_2 | SPI2_RX | SPI2_TX | SPI3_TX_1 | SPDIFRX_CS | SPI3_TX_2 |
+| Channel 1 | I2C1_RX | I2C3_RX | TIM7_UP_1 | - | TIM7_UP_2 | I2C1_RX_1 | I2C1_TX | I2C1_TX_1 |
+| Channel 2 | TIM4_CH1 | - | I2C4_RX | TIM4_CH2 | - | I2C4_TX | TIM4_UP | TIM4_CH3 |
+| Channel 3 | - | TIM2_UP_1 | I2C3_RX_1 | - | I2C3_TX | TIM2_CH1 | TIM2_CH2 | TIM2_UP_2 |
+| | | TIM2_CH3 | | | | | TIM2_CH4_1 | TIM2_CH4_2 |
+| Channel 4 | UART5_RX | USART3_RX | UART4_RX | USART3_TX_1 | UART4_TX | USART2_RX | USART2_TX | UART5_TX |
+| Channel 5 | UART8_TX | UART7_TX | TIM3_CH4 | UART7_RX | TIM3_CH1 | TIM3_CH2 | UART8_RX | TIM3_CH3 |
+| | | | TIM3_UP | | TIM3_TRIG | | | |
+| Channel 6 | TIM5_CH3 | TIM5_CH4_1 | TIM5_CH1 | TIM5_CH4_2 | TIM5_CH2 | - | TIM5_UP_2 | - |
+| | TIM5_UP_1 | TIM5_TRIG_1 | | TIM5_TRIG_2 | | | | |
+| Channel 7 | - | TIM6_UP | I2C2_RX | I2C2_RX_1 | USART3_TX_2 | DAC1 | DAC2 | I2C2_TX |
+| Channel 8 | I2C3_TX_1 | I2C4_RX_1 | - | - | I2C2_TX_1 | - | I2C4_TX_1 | - |
+| Channel 9 | - | SPI2_RX | - | - | - | - | SPI2_TX | - |
+| | | | | | | | | |
+| Usage | UART8_TX | USART3_RX | UART4_RX | USART3_TX_1 | | USART2_RX | UART8_RX | |
+
+
+| DMA2 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 |
+|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|
+| Channel 0 | ADC1_1 | SAI1_A | TIM8_CH1_1 | SAI1_A_2 | ADC1_2 | SAI1_B_1 | TIM1_CH1_1 | SAI1_B_2 |
+| | | | TIM8_CH2_1 | | | | TIM1_CH2_1 | |
+| | | | TIM8_CH3_1 | | | | TIM1_CH3_1 | |
+| Channel 1 | - | DCMI_1 | ADC2_1 | ADC2_2 | SAI1_B | SPI6_TX | SPI6_RX | DCMI_2 |
+| Channel 2 | ADC3_1 | ADC3_2 | - | SPI5_RX_1 | SPI5_TX_1 | CRYP_OUT | CRYP_IN | HASH_IN |
+| Channel 3 | SPI1_RX_1 | - | SPI1_RX_2 | SPI1_TX_1 | SAI2_A | SPI1_TX_2 | SAI2_B | QUADSPI |
+| Channel 4 | SPI4_RX_1 | SPI4_TX_1 | USART1_RX_1 | SDMMC1_1 | - | USART1_RX_2 | SDMMC1_2 | USART1_TX |
+| Channel 5 | - | USART6_RX_1 | USART6_RX_2 | SPI4_RX_2 | SPI4_TX_2 | - | USART6_TX_1 | USART6_TX_2 |
+| Channel 6 | TIM1_TRIG_1 | TIM1_CH1_2 | TIM1_CH2_2 | TIM1_CH1 | TIM1_CH4 | TIM1_UP | TIM1_CH3_2 | - |
+| | | | | | TIM1_TRIG_2 | | | |
+| | | | | | TIM1_COM | | | |
+| Channel 7 | - | TIM8_UP | TIM8_CH1_2 | TIM8_CH2_2 | TIM8_CH3_2 | SPI5_RX_2 | SPI5_TX_2 | TIM8_CH4 |
+| | | | | | | | | TIM8_TRIG |
+| | | | | | | | | TIM8_COM |
+| Channel 8 | DFSDM1_FLT0_1 | DFSDM1_FLT1_1 | DFSDM1_FLT2_1 | DFSDM1_FLT3_1 | DFSDM1_FLT0_2 | DFSDM1_FLT1_2 | DFSDM1_FLT2_2 | DFSDM1_FLT3_2 |
+| Channel 9 | JPEG_IN_1 | JPEG_OUT | SPI4_TX_3 | JPEG_IN_2 | JPEG_OUT_2 | SPI5_RX_3 | - | - |
+| Channel 10 | SAI1_B_3 | SAI2_B_1 | SAI2_A_1 | - | - | - | SAI1_A_3 | - |
+| Channel 11 | SDMMC2_1 | - | QUADSPI_1 | - | - | SDMMC2_2 | - | - |
+| | | | | | | | | |
+| Usage | SPI1_RX_1 | | USART6_RX_2 | SPI1_TX_1 | | TIM1_UP | SDMMC1_2 | |
+ */
+
+// DMA1 Channel/Stream Selections
+//--------------------------------------------//---------------------------//----------------
+// DMAMAP_UART8_TX // DMA1, Stream 0, Channel 5 (PX4IO TX)
+// DMAMAP_USART3_RX // DMA1, Stream 1, Channel 4 (TELEM2 RX)
+// DMAMAP_UART4_RX // DMA1, Stream 2, Channel 4 (TELEM4 RX)
+#define DMAMAP_USART3_TX DMAMAP_USART3_TX_1 // DMA1, Stream 3, Channel 4 (TELEM2 TX)
+// DMAMAP_USART2_RX // DMA1, Stream 5, Channel 4 (TELEM1 RX)
+// DMAMAP_UART8_RX // DMA1, Stream 6, Channel 5 (PX4IO RX)
+
+
+// DMA2 Channel/Stream Selections
+//--------------------------------------------//---------------------------//----------------
+#define DMAMAP_SPI1_RX DMAMAP_SPI1_RX_1 // DMA2, Stream 0, Channel 3 (SPI sensors RX)
+// AVAILABLE // DMA2, Stream 1
+#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2 // DMA2, Stream 2, Channel 5
+#define DMAMAP_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3 (SPI sensors TX)
+// AVAILABLE // DMA2, Stream 4
+// DMAMAP_TIM1_UP // DMA2, Stream 5, Channel 6 (DSHOT)
+#define DMAMAP_SDMMC1 DMAMAP_SDMMC1_2 // DMA2, Stream 6, Channel 4
+// AVAILABLE // DMA2, Stream 7
diff --git a/boards/atl/mantis-edu/nuttx-config/nsh/defconfig b/boards/atl/mantis-edu/nuttx-config/nsh/defconfig
new file mode 100644
index 000000000000..94f275a25bac
--- /dev/null
+++ b/boards/atl/mantis-edu/nuttx-config/nsh/defconfig
@@ -0,0 +1,238 @@
+#
+# This file is autogenerated: PLEASE DO NOT EDIT IT.
+#
+# You can use "make menuconfig" to make any modifications to the installed .config file.
+# You can then do "make savedefconfig" to generate a new defconfig file that includes your
+# modifications.
+#
+# CONFIG_DISABLE_ENVIRON is not set
+# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
+# CONFIG_FS_PROCFS_EXCLUDE_ENVIRON is not set
+# CONFIG_MMCSD_HAVE_CARDDETECT is not set
+# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
+# CONFIG_MMCSD_MMCSUPPORT is not set
+# CONFIG_MMCSD_SPI is not set
+# CONFIG_NSH_DISABLEBG is not set
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLE_DF is not set
+# CONFIG_NSH_DISABLE_EXEC is not set
+# CONFIG_NSH_DISABLE_EXIT is not set
+# CONFIG_NSH_DISABLE_GET is not set
+# CONFIG_NSH_DISABLE_ITEF is not set
+# CONFIG_NSH_DISABLE_LOOPS is not set
+# CONFIG_NSH_DISABLE_MKFATFS is not set
+# CONFIG_NSH_DISABLE_SEMICOLON is not set
+# CONFIG_NSH_DISABLE_TIME is not set
+CONFIG_ARCH="arm"
+CONFIG_ARCH_BOARD_CUSTOM=y
+CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/atl/mantis-edu/nuttx-config"
+CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
+CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
+CONFIG_ARCH_CHIP="stm32f7"
+CONFIG_ARCH_CHIP_STM32F765II=y
+CONFIG_ARCH_CHIP_STM32F7=y
+CONFIG_ARCH_INTERRUPTSTACK=512
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_ARMV7M_BASEPRI_WAR=y
+CONFIG_ARMV7M_DCACHE=y
+CONFIG_ARMV7M_DTCM=y
+CONFIG_ARMV7M_ICACHE=y
+CONFIG_ARMV7M_MEMCPY=y
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_ARM_MPU_EARLY_RESET=y
+CONFIG_BOARDCTL_RESET=y
+CONFIG_BOARD_CRASHDUMP=y
+CONFIG_BOARD_LOOPSPERMSEC=22114
+CONFIG_BOARD_RESET_ON_ASSERT=2
+CONFIG_BUILTIN=y
+CONFIG_C99_BOOL8=y
+CONFIG_CDCACM=y
+CONFIG_CDCACM_IFLOWCONTROL=y
+CONFIG_CDCACM_PRODUCTID=0x0061
+CONFIG_CDCACM_PRODUCTSTR="PX4 ATL Mantis-EDU"
+CONFIG_CDCACM_RXBUFSIZE=600
+CONFIG_CDCACM_TXBUFSIZE=12000
+CONFIG_CDCACM_VENDORID=0x26ac
+CONFIG_CDCACM_VENDORSTR="Advanced Technology Labs"
+CONFIG_CLOCK_MONOTONIC=y
+CONFIG_DEBUG_FULLOPT=y
+CONFIG_DEBUG_HARDFAULT_ALERT=y
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEFAULT_SMALL=y
+CONFIG_DEV_FIFO_SIZE=0
+CONFIG_DEV_PIPE_MAXSIZE=1024
+CONFIG_DEV_PIPE_SIZE=70
+CONFIG_DISABLE_MQUEUE=y
+CONFIG_FAT_DMAMEMORY=y
+CONFIG_FAT_LCNAMES=y
+CONFIG_FAT_LFN=y
+CONFIG_FAT_LFN_ALIAS_HASH=y
+CONFIG_FDCLONE_STDIO=y
+CONFIG_FS_BINFS=y
+CONFIG_FS_CROMFS=y
+CONFIG_FS_FAT=y
+CONFIG_FS_FATTIME=y
+CONFIG_FS_PROCFS=y
+CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
+CONFIG_FS_PROCFS_MAX_TASKS=64
+CONFIG_FS_PROCFS_REGISTER=y
+CONFIG_FS_ROMFS=y
+CONFIG_GRAN=y
+CONFIG_GRAN_INTR=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+CONFIG_I2C=y
+CONFIG_I2C_RESET=y
+CONFIG_IDLETHREAD_STACKSIZE=750
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_LIBC_LONG_LONG=y
+CONFIG_LIBC_STRERROR=y
+CONFIG_MEMSET_64BIT=y
+CONFIG_MEMSET_OPTSPEED=y
+CONFIG_MMCSD=y
+CONFIG_MMCSD_SDIO=y
+CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
+CONFIG_MM_REGIONS=3
+CONFIG_MTD=y
+CONFIG_MTD_BYTE_WRITE=y
+CONFIG_MTD_PARTITION=y
+CONFIG_MTD_RAMTRON=y
+CONFIG_NAME_MAX=40
+CONFIG_NSH_ARCHINIT=y
+CONFIG_NSH_ARGCAT=y
+CONFIG_NSH_BUILTIN_APPS=y
+CONFIG_NSH_CMDPARMS=y
+CONFIG_NSH_CROMFSETC=y
+CONFIG_NSH_DISABLE_IFCONFIG=y
+CONFIG_NSH_DISABLE_IFUPDOWN=y
+CONFIG_NSH_DISABLE_TELNETD=y
+CONFIG_NSH_LINELEN=128
+CONFIG_NSH_MAXARGUMENTS=15
+CONFIG_NSH_NESTDEPTH=8
+CONFIG_NSH_QUOTE=y
+CONFIG_NSH_ROMFSETC=y
+CONFIG_NSH_ROMFSSECTSIZE=128
+CONFIG_NSH_STRERROR=y
+CONFIG_NSH_VARS=y
+CONFIG_OTG_ID_GPIO_DISABLE=y
+CONFIG_PIPES=y
+CONFIG_PREALLOC_TIMERS=50
+CONFIG_PRIORITY_INHERITANCE=y
+CONFIG_PTHREAD_MUTEX_ROBUST=y
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_RAMTRON_SETSPEED=y
+CONFIG_RAM_SIZE=245760
+CONFIG_RAM_START=0x20010000
+CONFIG_RAW_BINARY=y
+CONFIG_READLINE_CMD_HISTORY=y
+CONFIG_READLINE_TABCOMPLETION=y
+CONFIG_RTC_DATETIME=y
+CONFIG_SCHED_ATEXIT=y
+CONFIG_SCHED_HPWORK=y
+CONFIG_SCHED_HPWORKPRIORITY=249
+CONFIG_SCHED_HPWORKSTACKSIZE=1280
+CONFIG_SCHED_INSTRUMENTATION=y
+CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
+CONFIG_SCHED_LPWORK=y
+CONFIG_SCHED_LPWORKPRIORITY=50
+CONFIG_SCHED_LPWORKSTACKSIZE=1632
+CONFIG_SCHED_WAITPID=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_SDMMC1_SDIO_MODE=y
+CONFIG_SDMMC1_SDIO_PULLUP=y
+CONFIG_SEM_PREALLOCHOLDERS=32
+CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
+CONFIG_SERIAL_TERMIOS=y
+CONFIG_SIG_DEFAULT=y
+CONFIG_SIG_SIGALRM_ACTION=y
+CONFIG_SIG_SIGUSR1_ACTION=y
+CONFIG_SIG_SIGUSR2_ACTION=y
+CONFIG_SIG_SIGWORK=4
+CONFIG_STACK_COLORATION=y
+CONFIG_START_DAY=30
+CONFIG_START_MONTH=11
+CONFIG_STDIO_BUFFER_SIZE=256
+CONFIG_STM32F7_ADC1=y
+CONFIG_STM32F7_BBSRAM=y
+CONFIG_STM32F7_BBSRAM_FILES=5
+CONFIG_STM32F7_BKPSRAM=y
+CONFIG_STM32F7_DMA1=y
+CONFIG_STM32F7_DMA2=y
+CONFIG_STM32F7_DMACAPABLE=y
+CONFIG_STM32F7_FLOWCONTROL_BROKEN=y
+CONFIG_STM32F7_I2C2=y
+CONFIG_STM32F7_I2C4=y
+CONFIG_STM32F7_I2C_DYNTIMEO=y
+CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10
+CONFIG_STM32F7_OTGFS=y
+CONFIG_STM32F7_PROGMEM=y
+CONFIG_STM32F7_PWR=y
+CONFIG_STM32F7_RTC=y
+CONFIG_STM32F7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y
+CONFIG_STM32F7_RTC_MAGIC_REG=1
+CONFIG_STM32F7_SAVE_CRASHDUMP=y
+CONFIG_STM32F7_SDMMC1=y
+CONFIG_STM32F7_SDMMC_DMA=y
+CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y
+CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y
+CONFIG_STM32F7_SPI1=y
+CONFIG_STM32F7_SPI1_DMA=y
+CONFIG_STM32F7_SPI1_DMA_BUFFER=1024
+CONFIG_STM32F7_SPI4=y
+CONFIG_STM32F7_SPI_DMA=y
+CONFIG_STM32F7_SPI_DMATHRESHOLD=8
+CONFIG_STM32F7_TIM10=y
+CONFIG_STM32F7_TIM11=y
+CONFIG_STM32F7_TIM3=y
+CONFIG_STM32F7_UART4=y
+CONFIG_STM32F7_UART5=y
+CONFIG_STM32F7_UART7=y
+CONFIG_STM32F7_UART8=y
+CONFIG_STM32F7_USART1=y
+CONFIG_STM32F7_USART2=y
+CONFIG_STM32F7_USART3=y
+CONFIG_STM32F7_USART6=y
+CONFIG_STM32F7_USART_BREAKS=y
+CONFIG_STM32F7_USART_INVERT=y
+CONFIG_STM32F7_USART_SINGLEWIRE=y
+CONFIG_STM32F7_USART_SWAP=y
+CONFIG_STM32F7_WWDG=y
+CONFIG_SYSTEM_CDCACM=y
+CONFIG_SYSTEM_NSH=y
+CONFIG_TASK_NAME_SIZE=24
+CONFIG_UART4_BAUD=57600
+CONFIG_UART4_RXBUFSIZE=600
+CONFIG_UART4_RXDMA=y
+CONFIG_UART4_TXBUFSIZE=3000
+CONFIG_UART7_BAUD=57600
+CONFIG_UART7_RXBUFSIZE=600
+CONFIG_UART7_TXBUFSIZE=1500
+CONFIG_UART8_BAUD=57600
+CONFIG_UART8_RXBUFSIZE=600
+CONFIG_UART8_SERIAL_CONSOLE=y
+CONFIG_UART8_TXBUFSIZE=1500
+CONFIG_USART1_BAUD=57600
+CONFIG_USART1_RXBUFSIZE=600
+CONFIG_USART1_TXBUFSIZE=1500
+CONFIG_USART2_BAUD=57600
+CONFIG_USART2_IFLOWCONTROL=y
+CONFIG_USART2_OFLOWCONTROL=y
+CONFIG_USART2_RXBUFSIZE=600
+CONFIG_USART2_RXDMA=y
+CONFIG_USART2_TXBUFSIZE=1500
+CONFIG_USART3_BAUD=57600
+CONFIG_USART3_IFLOWCONTROL=y
+CONFIG_USART3_OFLOWCONTROL=y
+CONFIG_USART3_RXBUFSIZE=600
+CONFIG_USART3_RXDMA=y
+CONFIG_USART3_TXBUFSIZE=3000
+CONFIG_USART6_BAUD=57600
+CONFIG_USART6_RXBUFSIZE=600
+CONFIG_USART6_RXDMA=y
+CONFIG_USART6_TXBUFSIZE=1500
+CONFIG_USBDEV=y
+CONFIG_USBDEV_BUSPOWERED=y
+CONFIG_USBDEV_MAXPOWER=500
+CONFIG_USEC_PER_TICK=1000
+CONFIG_USERMAIN_STACKSIZE=2944
+CONFIG_USER_ENTRYPOINT="nsh_main"
diff --git a/boards/atl/mantis-edu/nuttx-config/scripts/script.ld b/boards/atl/mantis-edu/nuttx-config/scripts/script.ld
new file mode 100644
index 000000000000..fc70ef1de834
--- /dev/null
+++ b/boards/atl/mantis-edu/nuttx-config/scripts/script.ld
@@ -0,0 +1,191 @@
+/****************************************************************************
+ * scripts/script.ld
+ *
+ * Copyright (C) 2016 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/* The STM32F765IIT6 has 2048 KiB of main FLASH memory. This FLASH memory
+ * can be accessed from either the AXIM interface at address 0x0800:0000 or
+ * from the ITCM interface at address 0x0020:0000.
+ *
+ * Additional information, including the option bytes, is available at at
+ * FLASH at address 0x1ff0:0000 (AXIM) or 0x0010:0000 (ITCM).
+ *
+ * In the STM32F765IIT6, two different boot spaces can be selected through
+ * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and
+ * BOOT_ADD1 option bytes:
+ *
+ * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0].
+ * ST programmed value: Flash on ITCM at 0x0020:0000
+ * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
+ * ST programmed value: System bootloader at 0x0010:0000
+ *
+ * NuttX does not modify these option byes. On the unmodified NUCLEO-144
+ * board, the BOOT0 pin is at ground so by default, the STM32F765IIT6 will
+ * boot from address 0x0020:0000 in ITCM FLASH.
+ *
+ * The STM32F765IIT6 also has 512 KiB of data SRAM (in addition to ITCM SRAM).
+ * SRAM is split up into three blocks:
+ *
+ * 1) 128 KiB of DTCM SRM beginning at address 0x2000:0000
+ * 2) 368 KiB of SRAM1 beginning at address 0x2002:0000
+ * 3) 16 KiB of SRAM2 beginning at address 0x2007:c000
+ *
+ * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
+ * where the code expects to begin execution by jumping to the entry point in
+ * the 0x0800:0000 address range.
+ *
+ * Bootloader reserves the first 32K bank (2 Mbytes Flash memory single bank)
+ * organization (256 bits read width)
+ * The next 2 32K sectors are reserved for parameters.
+ */
+
+MEMORY
+{
+ FLASH_ITCM (rx) : ORIGIN = 0x00218000, LENGTH = 1952K
+ FLASH_AXIM (rx) : ORIGIN = 0x08018000, LENGTH = 1952K
+
+ ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K
+ DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
+ SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K
+ SRAM2 (rwx) : ORIGIN = 0x2007c000, LENGTH = 16K
+}
+
+OUTPUT_ARCH(arm)
+EXTERN(_vectors)
+ENTRY(_stext)
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+EXTERN(_bootdelay_signature)
+EXTERN(_main_toc)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ . = ALIGN(32);
+ /*
+ This signature provides the bootloader with a way to delay booting
+ */
+ _bootdelay_signature = ABSOLUTE(.);
+ FILL(0xb4ecc2925d7d05c5)
+ . += 8;
+ *(.main_toc)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+
+ } > FLASH_AXIM
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > FLASH_AXIM
+
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > FLASH_AXIM
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > FLASH_AXIM
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > SRAM1 AT > FLASH_AXIM
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = ABSOLUTE(.);
+ } > SRAM1
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+
+ .ramfunc : {
+ _sramfuncs = .;
+ *(.ramfunc .ramfunc.*)
+ . = ALIGN(4);
+ _eramfuncs = .;
+ } > ITCM_RAM AT > FLASH_AXIM
+
+ _framfuncs = LOADADDR(.ramfunc);
+
+ /* Start of the image signature. This
+ * has to be in the end of the image
+ */
+ .signature : {
+ _boot_signature = ALIGN(4);
+ } > FLASH_AXIM
+}
diff --git a/boards/atl/mantis-edu/src/CMakeLists.txt b/boards/atl/mantis-edu/src/CMakeLists.txt
new file mode 100644
index 000000000000..398389f97d00
--- /dev/null
+++ b/boards/atl/mantis-edu/src/CMakeLists.txt
@@ -0,0 +1,54 @@
+############################################################################
+#
+# Copyright (c) 2016 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+add_library(drivers_board
+ i2c.cpp
+ init.c
+ led.c
+ sdio.c
+ spi.cpp
+ timer_config.cpp
+ usb.c
+ pwr.cpp
+)
+add_dependencies(drivers_board arch_board_hw_info)
+
+target_link_libraries(drivers_board
+ PRIVATE
+ arch_board_hw_info
+ arch_spi
+ drivers__led # drv_led_start
+ nuttx_arch # sdio
+ nuttx_drivers # sdio
+ px4_layer
+)
diff --git a/boards/atl/mantis-edu/src/board_config.h b/boards/atl/mantis-edu/src/board_config.h
new file mode 100644
index 000000000000..2342446c131b
--- /dev/null
+++ b/boards/atl/mantis-edu/src/board_config.h
@@ -0,0 +1,229 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2016 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file board_config.h
+ *
+ * PX4FMU-v5 internal definitions
+ */
+
+#pragma once
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include
+#include
+#include
+
+#include
+
+/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */
+#define GPIO_nLED_RED /* PB1 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_nLED_GREEN /* PC6 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN6)
+#define GPIO_nLED_BLUE /* PC7 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7)
+
+#define BOARD_HAS_CONTROL_STATUS_LEDS 1
+#define BOARD_OVERLOAD_LED LED_RED
+#define BOARD_ARMED_STATE_LED LED_BLUE
+
+#define FLASH_BASED_PARAMS
+#define RAM_BASED_MISSIONS
+
+// Hacks for MAVLink RC button input
+#define ATL_MANTIS_RC_INPUT_HACKS
+
+// Hacks for MAVLink RC button input
+#define ATL_MANTIS_RC_INPUT_HACKS
+
+/*
+ * ADC channels
+ *
+ * These are the channel numbers of the ADCs of the microcontroller that
+ * can be used by the Px4 Firmware in the adc driver
+ */
+
+/* ADC defines to be used in sensors.cpp to read from a particular channel */
+#define ADC1_CH(n) (n)
+#define ADC1_GPIO(n) GPIO_ADC1_IN##n
+
+/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
+
+#define PX4_ADC_GPIO \
+ /* PA0 */ ADC1_GPIO(0), \
+ /* PC0 */ ADC1_GPIO(10), \
+ /* PC1 */ ADC1_GPIO(11), \
+ /* PC2 */ ADC1_GPIO(12), \
+ /* PC3 */ ADC1_GPIO(13), \
+ /* PC4 */ ADC1_GPIO(14)
+
+/* Define Channel numbers must match above GPIO pin IN(n)*/
+#define ADC_BATTERY_VOLTAGE_CHANNEL /* PA0 */ ADC1_CH(0)
+#define ADC_BATTERY_CURRENT_CHANNEL 0
+#define ADC_SCALED_V5_CHANNEL /* PC0 */ ADC1_CH(10)
+#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL /* PC1 */ ADC1_CH(11)
+#define ADC_HW_VER_SENSE_CHANNEL /* PC2 */ ADC1_CH(12)
+#define ADC_HW_REV_SENSE_CHANNEL /* PC3 */ ADC1_CH(13)
+#define ADC1_SPARE_1_CHANNEL /* PC4 */ ADC1_CH(14) // POWER_AD
+
+#define ADC_CHANNELS \
+ ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
+ (1 << ADC_SCALED_V5_CHANNEL) | \
+ (1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \
+ (1 << ADC_HW_VER_SENSE_CHANNEL) | \
+ (1 << ADC_HW_REV_SENSE_CHANNEL) | \
+ (1 << ADC1_SPARE_1_CHANNEL))
+
+/* HW has to large of R termination on ADC todo:change when HW value is chosen */
+#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
+
+/* HW Version and Revision drive signals Default to 1 to detect */
+#define BOARD_HAS_HW_VERSIONING
+
+#define GPIO_HW_REV_DRIVE /* PH14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN14)
+#define GPIO_HW_REV_SENSE /* PC3 */ ADC1_GPIO(13)
+#define GPIO_HW_VER_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
+#define GPIO_HW_VER_SENSE /* PC2 */ ADC1_GPIO(12)
+#define HW_INFO_INIT {'V','5','x', 'x',0}
+#define HW_INFO_INIT_VER 2
+#define HW_INFO_INIT_REV 3
+
+#define BOARD_TAP_ESC_MODE 2 // select closed-loop control mode for the esc
+// #define BOARD_USE_ESC_CURRENT_REPORT
+
+// LED mapping
+#define BOARD_FRONT_LED_MASK (1 << 0) | (1 << 3)
+#define BOARD_REAR_LED_MASK (1 << 1) | (1 << 2)
+
+/* HEATER */
+#define GPIO_HEATER_OUTPUT /* PA7 T14CH1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN7)
+
+#define BOARD_HAS_LED_PWM 1
+#define BOARD_LED_PWM_DRIVE_ACTIVE_LOW 1
+
+#define BOARD_UI_LED_PWM_DRIVE_ACTIVE_LOW 1
+
+#define BOARD_ADC_BRICK_VALID 1
+#define BOARD_NUMBER_BRICKS 1
+
+#define GPIO_VDD_3V3_SD_CARD_EN /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN7)
+#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true))
+
+/* USB OTG FS */
+#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
+
+/* High-resolution timer */
+#define HRT_TIMER 8 /* use timer8 for the HRT */
+#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
+
+/* RC Serial port */
+#define RC_SERIAL_PORT "/dev/ttyS5"
+#define RC_SERIAL_SINGLEWIRE
+
+/* power on/off */
+#define MS_PWR_BUTTON_DOWN 750
+#define KEY_AD_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_EXTI|GPIO_PORTC|GPIO_PIN4)
+#define POWER_ON_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
+#define POWER_OFF_GPIO (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTC|GPIO_PIN5)
+#define POWER_CHECK_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN0)
+
+#define SDIO_SLOTNO 0 /* Only one slot */
+#define SDIO_MINOR 0
+
+/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
+ * this board support the ADC system_power interface, and therefore
+ * provides the true logic GPIO BOARD_ADC_xxxx macros.
+ */
+#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS))
+#define BOARD_ADC_USB_VALID BOARD_ADC_USB_CONNECTED
+
+/* FMUv5 never powers odd the Servo rail */
+#define BOARD_ADC_SERVO_VALID (1)
+
+#define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
+#define BOARD_ADC_BRICK2_VALID (0)
+
+/* This board provides a DMA pool and APIs */
+#define BOARD_DMA_ALLOC_POOL_SIZE 5120
+
+/* This board provides the board_on_reset interface */
+#define BOARD_HAS_ON_RESET 1
+#define BOARD_HAS_POWER_CONTROL 1
+
+#define GPIO_CAM_PWR_ON_H /* PB0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_CAM_PWR_ON_L /* PB0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
+
+#define PX4_GPIO_INIT_LIST { \
+ PX4_ADC_GPIO, \
+ GPIO_HW_REV_DRIVE, \
+ GPIO_HW_VER_DRIVE, \
+ GPIO_HEATER_OUTPUT, \
+ GPIO_VDD_3V3_SD_CARD_EN, \
+ GPIO_OTGFS_VBUS \
+ }
+
+#define BOARD_ENABLE_CONSOLE_BUFFER
+
+#define BOARD_NUM_IO_TIMERS 1
+
+__BEGIN_DECLS
+
+#ifndef __ASSEMBLY__
+
+int stm32_sdio_initialize(void);
+
+extern void stm32_spiinitialize(void);
+
+extern void stm32_usbinitialize(void);
+
+extern void board_peripheral_reset(int ms);
+
+/************************************************************************************
+ * Name: board_pwr_init()
+ *
+ * Description:
+ * Called to configure power control for the tap-v2 board.
+ *
+ * Input Parameters:
+ * stage- 0 for boot, 1 for board init
+ *
+ ************************************************************************************/
+
+void board_pwr_init(int stage);
+
+#include
+
+#endif /* __ASSEMBLY__ */
+
+__END_DECLS
diff --git a/boards/atl/mantis-edu/src/i2c.cpp b/boards/atl/mantis-edu/src/i2c.cpp
new file mode 100644
index 000000000000..781fbaf7312f
--- /dev/null
+++ b/boards/atl/mantis-edu/src/i2c.cpp
@@ -0,0 +1,39 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2020 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#include
+
+constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
+ initI2CBusInternal(2),
+ initI2CBusInternal(4),
+};
diff --git a/boards/atl/mantis-edu/src/init.c b/boards/atl/mantis-edu/src/init.c
new file mode 100644
index 000000000000..461c16377e1a
--- /dev/null
+++ b/boards/atl/mantis-edu/src/init.c
@@ -0,0 +1,271 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012-2019 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 init.c
+ *
+ * PX4FMU-specific early startup code. This file implements the
+ * board_app_initializ() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialisation.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include "board_config.h"
+
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include "arm_internal.h"
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+# if defined(FLASH_BASED_PARAMS)
+# include
+#endif
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+#define _GPIO_PULL_DOWN_INPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz))
+
+/* Configuration ************************************************************/
+
+/*
+ * Ideally we'd be able to get these from arm_internal.h,
+ * but since we want to be able to disable the NuttX use
+ * of leds for system indication at will and there is no
+ * separate switch, we need to build independent of the
+ * CONFIG_ARCH_LEDS configuration switch.
+ */
+__BEGIN_DECLS
+extern void led_init(void);
+extern void led_on(int led);
+extern void led_off(int led);
+__END_DECLS
+
+/***************cam_pwr_on_pulse*****************************************************
+ * Name: cam_pwr_on_pulse()
+ *
+ * Description:
+ * Camera power is controlled by flight control, send a risingedge pulse to enable it
+ *
+ *
+ * Input Parameters:
+ * Not used
+ *
+ ************************************************************************************/
+static void cam_pwr_on_pulse(void)
+{
+ static bool pwr_on_flag = false;
+
+ if (pwr_on_flag == false) {
+ // This is now done in the bootloader.
+ // However, for transition we can leave it in.
+ up_mdelay(700);
+ stm32_configgpio(GPIO_CAM_PWR_ON_H);
+ up_mdelay(20);
+ stm32_configgpio(GPIO_CAM_PWR_ON_L);
+
+ pwr_on_flag = true;
+ }
+}
+/************************************************************************************
+ * Name: board_peripheral_reset
+ *
+ * Description:
+ *
+ ************************************************************************************/
+__EXPORT void board_peripheral_reset(int ms)
+{
+}
+
+/************************************************************************************
+ * Name: board_on_reset
+ *
+ * Description:
+ * Optionally provided function called on entry to board_system_reset
+ * It should perform any house keeping prior to the rest.
+ *
+ * status - 1 if resetting to boot loader
+ * 0 if just resetting
+ *
+ ************************************************************************************/
+__EXPORT void board_on_reset(int status)
+{
+}
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the initialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_boardinitialize(void)
+{
+ /* Hold power state */
+ board_pwr_init(0);
+
+ /* configure pins */
+ const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
+ px4_gpio_init(gpio, arraySize(gpio));
+ board_control_spi_sensors_power_configgpio();
+}
+
+/****************************************************************************
+ * Name: board_app_initialize
+ *
+ * Description:
+ * Perform application specific initialization. This function is never
+ * called directly from application code, but only indirectly via the
+ * (non-standard) boardctl() interface using the command BOARDIOC_INIT.
+ *
+ * Input Parameters:
+ * arg - The boardctl() argument is passed to the board_app_initialize()
+ * implementation without modification. The argument has no
+ * meaning to NuttX; the meaning of the argument is a contract
+ * between the board-specific initalization logic and the the
+ * matching application logic. The value cold be such things as a
+ * mode enumeration value, a set of DIP switch switch settings, a
+ * pointer to configuration data read from a file or serial FLASH,
+ * or whatever you would like to do with it. Every implementation
+ * should accept zero/NULL as a default configuration.
+ *
+ * Returned Value:
+ * Zero (OK) is returned on success; a negated errno value is returned on
+ * any failure to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+__EXPORT int board_app_initialize(uintptr_t arg)
+{
+ /* Power on Interfaces */
+ VDD_3V3_SD_CARD_EN(true);
+
+ /* Need hrt running before using the ADC */
+ px4_platform_init();
+
+ if (OK == board_determine_hw_info()) {
+ syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
+ board_get_hw_type_name());
+
+ } else {
+ syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n");
+ }
+
+ /* configure SPI interfaces (after we determined the HW version) */
+ stm32_spiinitialize();
+
+ /* configure the DMA allocator */
+ if (board_dma_alloc_init() < 0) {
+ syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
+ }
+
+#if defined(SERIAL_HAVE_RXDMA)
+ // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
+ static struct hrt_call serial_dma_call;
+ hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
+#endif
+
+ board_pwr_init(1);
+
+ /* initial LED state */
+ drv_led_start();
+ led_off(LED_RED);
+ led_on(LED_GREEN); // Indicate Power.
+ led_off(LED_BLUE);
+
+ if (board_hardfault_init(2, true) != 0) {
+ led_on(LED_RED);
+ }
+
+#if defined(CONFIG_MMCSD)
+ int ret = stm32_sdio_initialize();
+
+ if (ret != OK) {
+ led_on(LED_RED);
+ }
+
+#endif /* CONFIG_MMCSD */
+
+ /* Camera power is controlled by flight control, send a risingedge pulse to enable it */
+ cam_pwr_on_pulse();
+
+#if defined(FLASH_BASED_PARAMS)
+ static sector_descriptor_t params_sector_map[] = {
+ {1, 32 * 1024, 0x08008000},
+ {2, 32 * 1024, 0x08010000},
+ {0, 0, 0},
+ };
+
+ /* Initialize the flashfs layer to use heap allocated memory */
+ int result = parameter_flashfs_init(params_sector_map, NULL, 0);
+
+ if (result != OK) {
+ syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
+ led_on(LED_AMBER);
+ return result;
+ }
+
+#endif /* FLASH_BASED_PARAMS */
+
+ return OK;
+}
diff --git a/boards/atl/mantis-edu/src/led.c b/boards/atl/mantis-edu/src/led.c
new file mode 100644
index 000000000000..bafff9ccdbd6
--- /dev/null
+++ b/boards/atl/mantis-edu/src/led.c
@@ -0,0 +1,104 @@
+/****************************************************************************
+ *
+ * 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 led.c
+ *
+ * PX4FMU LED backend.
+ */
+
+#include
+
+#include