aboutsummaryrefslogtreecommitdiff
path: root/Tools
diff options
context:
space:
mode:
Diffstat (limited to 'Tools')
-rw-r--r--Tools/Matlab/motors.m58
-rwxr-xr-xTools/boot_now.py59
-rwxr-xr-xTools/check_code_style.sh3
-rwxr-xr-xTools/check_submodules.sh22
-rwxr-xr-xTools/px_uploader.py30
-rwxr-xr-xTools/ros/px4_ros_installation_ubuntu.sh2
-rwxr-xr-xTools/ros/px4_workspace_setup.sh8
7 files changed, 173 insertions, 9 deletions
diff --git a/Tools/Matlab/motors.m b/Tools/Matlab/motors.m
new file mode 100644
index 000000000..6d688a307
--- /dev/null
+++ b/Tools/Matlab/motors.m
@@ -0,0 +1,58 @@
+clear all;
+close all;
+
+% Measurement data
+% 1045 propeller
+% Robbe Roxxy Motor (1100 kV, data collected in 2010)
+data = [ 45, 7.4;...
+ 38, 5.6;...
+ 33, 4.3;...
+ 26, 3.0;...
+ 18, 2.0;...
+ 10, 1.0 ];
+
+% Normalize the data, as we're operating later
+% anyways in normalized units
+data(:,1) = data(:,1) ./ max(data(:,1));
+data(:,2) = data(:,2) ./ max(data(:,2));
+
+% Fit a 2nd degree polygon to the data and
+% print the x2, x1, x0 coefficients
+p = polyfit(data(:,2), data(:,1),2)
+
+% Override the first coffefficient for testing
+% purposes
+pf = 0.62;
+
+% Generate plotting data
+px1 = linspace(0, max(data(:,2)));
+py1 = polyval(p, px1);
+
+pyt = zeros(size(data, 1), 1);
+corr = zeros(size(data, 1), 1);
+
+% Actual code test
+% the two lines below are the ones needed to be ported to C:
+% pf: Power factor parameter.
+% px1(i): The current normalized motor command (-1..1)
+% corr(i): The required correction. The motor speed is:
+% px1(i)
+for i=1:size(px1, 2)
+
+ % The actual output throttle
+ pyt(i) = -pf * (px1(i) * px1(i)) + (1 + pf) * px1(i);
+
+ % Solve for input throttle
+ % y = -p * x^2 + (1+p) * x;
+ %
+end
+
+plot(data(:,2), data(:,1), '*r');
+hold on;
+plot(px1, py1, '*b');
+hold on;
+plot([0 px1(end)], [0 py1(end)], '-k');
+hold on;
+plot(px1, pyt, '-b');
+hold on;
+plot(px1, corr, '-m');
diff --git a/Tools/boot_now.py b/Tools/boot_now.py
new file mode 100755
index 000000000..5a9e608da
--- /dev/null
+++ b/Tools/boot_now.py
@@ -0,0 +1,59 @@
+#!/usr/bin/env python
+############################################################################
+#
+# Copyright (C) 2012-2015 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# send BOOT command to a device
+
+import argparse
+import serial, sys
+
+from sys import platform as _platform
+
+# Parse commandline arguments
+parser = argparse.ArgumentParser(description="Send boot command to a device")
+parser.add_argument('--baud', action="store", type=int, default=115200, help="Baud rate of the serial port")
+parser.add_argument('port', action="store", help="Serial port(s) to which the FMU may be attached")
+args = parser.parse_args()
+
+REBOOT = b'\x30'
+EOC = b'\x20'
+
+print("Sending reboot to %s" % args.port)
+try:
+ port = serial.Serial(args.port, args.baud, timeout=0.5)
+except Exception:
+ print("Unable to open %s" % args.port)
+ sys.exit(1)
+port.write(REBOOT + EOC)
+port.close()
+sys.exit(0)
diff --git a/Tools/check_code_style.sh b/Tools/check_code_style.sh
index 8d1ab6363..b8806f316 100755
--- a/Tools/check_code_style.sh
+++ b/Tools/check_code_style.sh
@@ -3,7 +3,8 @@ set -eu
failed=0
for fn in $(find . -path './src/lib/uavcan' -prune -o \
-path './src/lib/mathlib/CMSIS' -prune -o \
- -path './src/modules/attitude_estimator_ekf/codegen/' -prune -o \
+ -path './src/lib/eigen' -prune -o \
+ -path './src/modules/attitude_estimator_ekf/codegen' -prune -o \
-path './NuttX' -prune -o \
-path './Build' -prune -o \
-path './mavlink' -prune -o \
diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh
index 5e6e57164..4b251642c 100755
--- a/Tools/check_submodules.sh
+++ b/Tools/check_submodules.sh
@@ -74,6 +74,28 @@ else
git submodule update;
fi
+if [ -d src/lib/eigen ]
+then
+ STATUSRETVAL=$(git submodule summary | grep -A20 -i eigen | grep "<")
+ if [ -z "$STATUSRETVAL" ]
+ then
+ echo "Checked Eigen submodule, correct version found"
+ else
+ echo ""
+ echo ""
+ echo "New commits required:"
+ echo "$(git submodule summary)"
+ echo ""
+ echo ""
+ echo "eigen sub repo not at correct version. Try 'git submodule update'"
+ echo "or follow instructions on http://pixhawk.org/dev/git/submodules"
+ exit 1
+ fi
+else
+ git submodule init;
+ git submodule update;
+fi
+
if [ -d Tools/gencpp ]
then
STATUSRETVAL=$(git submodule summary | grep -A20 -i gencpp | grep "<")
diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py
index 859c821e5..3cdd9d1a6 100755
--- a/Tools/px_uploader.py
+++ b/Tools/px_uploader.py
@@ -160,6 +160,8 @@ class uploader(object):
GET_CRC = b'\x29' # rev3+
GET_OTP = b'\x2a' # rev4+ , get a word from OTP area
GET_SN = b'\x2b' # rev4+ , get a word from SN area
+ GET_CHIP = b'\x2c' # rev5+ , get chip version
+ SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay
REBOOT = b'\x30'
INFO_BL_REV = b'\x01' # bootloader protocol revision
@@ -258,7 +260,7 @@ class uploader(object):
self.__getSync()
return value
- # send the GET_OTP command and wait for an info parameter
+ # send the GET_SN command and wait for an info parameter
def __getSN(self, param):
t = struct.pack("I", param) # int param as 32bit ( 4 byte ) char array.
self.__send(uploader.GET_SN + t + uploader.EOC)
@@ -266,6 +268,13 @@ class uploader(object):
self.__getSync()
return value
+ # send the GET_CHIP command
+ def __getCHIP(self):
+ self.__send(uploader.GET_CHIP + uploader.EOC)
+ value = self.__recv_int()
+ self.__getSync()
+ return value
+
def __drawProgressBar(self, label, progress, maxVal):
if maxVal < progress:
progress = maxVal
@@ -397,6 +406,12 @@ class uploader(object):
raise RuntimeError("Program CRC failed")
self.__drawProgressBar(label, 100, 100)
+ def __set_boot_delay(self, boot_delay):
+ self.__send(uploader.SET_BOOT_DELAY
+ + struct.pack("b", boot_delay)
+ + uploader.EOC)
+ self.__getSync()
+
# get basic data about the board
def identify(self):
# make sure we are in sync before starting
@@ -416,7 +431,12 @@ class uploader(object):
def upload(self, fw):
# Make sure we are doing the right thing
if self.board_type != fw.property('board_id'):
- raise IOError("Firmware not suitable for this board")
+ msg = "Firmware not suitable for this board (board_type=%u board_id=%u)" % (
+ self.board_type, fw.property('board_id'))
+ if args.force:
+ print("WARNING: %s" % msg)
+ else:
+ raise IOError(msg)
if self.fw_maxsize < fw.property('image_size'):
raise RuntimeError("Firmware image is too large for this board")
@@ -446,6 +466,7 @@ class uploader(object):
self.sn = self.sn + x
print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
print('')
+ print("chip: %08x" % self.__getCHIP())
except Exception:
# ignore bad character encodings
pass
@@ -458,6 +479,9 @@ class uploader(object):
else:
self.__verify_v3("Verify ", fw)
+ if args.boot_delay is not None:
+ self.__set_boot_delay(args.boot_delay)
+
print("\nRebooting.\n")
self.__reboot()
self.port.close()
@@ -486,6 +510,8 @@ else:
parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.")
parser.add_argument('--port', action="store", required=True, help="Serial port(s) to which the FMU may be attached")
parser.add_argument('--baud', action="store", type=int, default=115200, help="Baud rate of the serial port (default is 115200), only required for true serial ports.")
+parser.add_argument('--force', action='store_true', default=False, help='Override board type check and continue loading')
+parser.add_argument('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash')
parser.add_argument('firmware', action="store", help="Firmware file to be uploaded")
args = parser.parse_args()
diff --git a/Tools/ros/px4_ros_installation_ubuntu.sh b/Tools/ros/px4_ros_installation_ubuntu.sh
index 7efc400cd..b65df8dce 100755
--- a/Tools/ros/px4_ros_installation_ubuntu.sh
+++ b/Tools/ros/px4_ros_installation_ubuntu.sh
@@ -27,7 +27,7 @@ echo "source /opt/ros/indigo/setup.bash" >> ~/.bashrc
sudo apt-get -y install python-rosinstall
# additional dependencies
-sudo apt-get -y install ros-indigo-octomap-msgs ros-indigo-joy
+sudo apt-get -y install ros-indigo-octomap-msgs ros-indigo-joy ros-indigo-mavros ros-indigo-mavros-extras
## drcsim setup (for models)
### add osrf repository
diff --git a/Tools/ros/px4_workspace_setup.sh b/Tools/ros/px4_workspace_setup.sh
index 3e4bf06a5..5599ab999 100755
--- a/Tools/ros/px4_workspace_setup.sh
+++ b/Tools/ros/px4_workspace_setup.sh
@@ -10,21 +10,19 @@ git clone https://github.com/PX4/Firmware.git
# euroc simulator
git clone https://github.com/PX4/euroc_simulator.git
-cd euroc_simulator
-git checkout px4_nodes
-cd ..
# mav comm
git clone https://github.com/PX4/mav_comm.git
+# gflags catkin
+git clone https://github.com/ethz-asl/gflags_catkin.git
+
# glog catkin
git clone https://github.com/ethz-asl/glog_catkin.git
# catkin simple
git clone https://github.com/catkin/catkin_simple.git
-# drcsim (for scenery and models)
-
cd ..
catkin_make