aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorAndrew Tridgell <andrew@tridgell.net>2015-02-06 18:38:14 +1100
committerAndrew Tridgell <andrew@tridgell.net>2015-02-11 17:36:07 +1100
commitfc40a5c64155a828bc070c815c61ad7f7244fb5d (patch)
tree895378e872149c74de84aa1f4c64ce6e6eb71cba /src
parent6774c3b2131da287650deff8151be992c896f830 (diff)
downloadpx4-firmware-fc40a5c64155a828bc070c815c61ad7f7244fb5d.tar.gz
px4-firmware-fc40a5c64155a828bc070c815c61ad7f7244fb5d.tar.bz2
px4-firmware-fc40a5c64155a828bc070c815c61ad7f7244fb5d.zip
systemcmds: added usb_connected command
this is used in APM startup to see if we should start nsh on usb when no microSD is inserted
Diffstat (limited to 'src')
-rw-r--r--src/systemcmds/usb_connected/module.mk37
-rw-r--r--src/systemcmds/usb_connected/usb_connected.c56
2 files changed, 93 insertions, 0 deletions
diff --git a/src/systemcmds/usb_connected/module.mk b/src/systemcmds/usb_connected/module.mk
new file mode 100644
index 000000000..22ee1300d
--- /dev/null
+++ b/src/systemcmds/usb_connected/module.mk
@@ -0,0 +1,37 @@
+############################################################################
+#
+# Copyright (c) 2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+MODULE_COMMAND = usb_connected
+SRCS = usb_connected.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/usb_connected/usb_connected.c b/src/systemcmds/usb_connected/usb_connected.c
new file mode 100644
index 000000000..98bbbc4be
--- /dev/null
+++ b/src/systemcmds/usb_connected/usb_connected.c
@@ -0,0 +1,56 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 Andrew Tridgell. 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 usb_connected.c
+ *
+ * utility to check if USB is connected. Used in startup scripts
+ *
+ * @author Andrew Tridgell
+ */
+
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <drivers/drv_gpio.h>
+#include <arch/board/board.h>
+#include <board_config.h>
+
+__EXPORT int usb_connected_main(int argc, char *argv[]);
+
+int
+usb_connected_main(int argc, char *argv[])
+{
+ return stm32_gpioread(GPIO_OTGFS_VBUS) ? 0:1;
+}