diff --git a/Tools/Linux_HAL_Essentials/scripts/start_plane.sh b/Tools/Linux_HAL_Essentials/scripts/start_plane.sh deleted file mode 100755 index 41fd782cee..0000000000 --- a/Tools/Linux_HAL_Essentials/scripts/start_plane.sh +++ /dev/null @@ -1,13 +0,0 @@ -#!/bin/bash - -cd /root -( - date - init 3 - killall -q udhcpd - (cd Linux_HAL_Essentials && ./startup.sh load) - while :; do - ./ArduPlane.elf -A /dev/ttyO0 -B /dev/ttyO5 - done -) >> plane.log 2>&1 - diff --git a/Tools/Linux_HAL_Essentials/sensor-select.sh b/Tools/Linux_HAL_Essentials/sensor-select.sh deleted file mode 100755 index 0b69090e8d..0000000000 --- a/Tools/Linux_HAL_Essentials/sensor-select.sh +++ /dev/null @@ -1,33 +0,0 @@ -#!/bin/bash - -# This script allows you to select which sensors you can use. For now it's resctricted to IMU use -# Coded by VĂ­ctor Mayoral Vilches - -IMU_CONFIG=$(grep -A 5 "#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD" ../../libraries/AP_HAL/AP_HAL_Boards.h| grep HAL_INS_DEFAULT) -echo "Current setup is: "$IMU_CONFIG - -if [ $# -eq 0 ] - then - echo "No arguments supplied. Please provide one of the following sensors: mpu6000, mpu9250, lsm9ds0" - echo " Usage: source sensor-select.sh " - return 0 -fi - -if [ $1 == "mpu6000" ] -then - sed -i "s/$IMU_CONFIG/#define HAL_INS_DEFAULT HAL_INS_MPU6000/g" ../../libraries/AP_HAL/AP_HAL_Boards.h - echo "MPU6000 selected" -elif [ $1 == "mpu9250" ] -then - sed -i "s/$IMU_CONFIG/#define HAL_INS_DEFAULT HAL_INS_MPU9250/g" ../../libraries/AP_HAL/AP_HAL_Boards.h - echo "MPU9250 selected" -elif [ $1 == "lsm9ds0" ] -then - sed -i "s/$IMU_CONFIG/#define HAL_INS_DEFAULT HAL_INS_LSM9DS0/g" ../../libraries/AP_HAL/AP_HAL_Boards.h - echo "LSM9DS0 selected" -else - echo "Sensor supplied invaled. Please provide one of the following sensors: mpu6000, mpu9250, lsm9ds0" - echo " Usage: source sensor-select.sh " - return 0 -fi - diff --git a/Tools/Linux_HAL_Essentials/test_codes/rcin_test.c b/Tools/Linux_HAL_Essentials/test_codes/rcin_test.c deleted file mode 100644 index 8e533630e8..0000000000 --- a/Tools/Linux_HAL_Essentials/test_codes/rcin_test.c +++ /dev/null @@ -1,55 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#define PRUSS_SHAREDRAM_BASE 0x4a312000 -#define NUM_RING_ENTRIES 200 - -struct ring_buffer { - volatile uint16_t ring_head; - volatile uint16_t ring_tail; - struct __attribute__((__packed__)) { - uint16_t pin_value; - uint16_t delta_t; - } buffer[NUM_RING_ENTRIES]; -}; - -static volatile struct ring_buffer *ring_buffer; -static FILE *logf; - - -void startup(void) -{ - logf = fopen("/tmp/pintiming.dat", "w"); -} - -void check_for_rcin(void) -{ - while (ring_buffer->ring_head != ring_buffer->ring_tail) { - fprintf(logf,"%u %u\n", - (unsigned int)ring_buffer->buffer[ring_buffer->ring_head].pin_value, - (unsigned int)ring_buffer->buffer[ring_buffer->ring_head].delta_t); - ring_buffer->ring_head = (ring_buffer->ring_head + 1) % NUM_RING_ENTRIES; - } -} - -void main(){ - - int mem_fd = open("/dev/mem", O_RDWR|O_SYNC); - ring_buffer = (volatile struct ring_buffer*) mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, PRUSS_SHAREDRAM_BASE); - close(mem_fd); - ring_buffer->ring_head = 0; - startup(); - while(1){ - check_for_rcin(); - } -} diff --git a/Tools/PXF/check_CS.sh b/Tools/PXF/check_CS.sh deleted file mode 100644 index 9c9120280d..0000000000 --- a/Tools/PXF/check_CS.sh +++ /dev/null @@ -1,17 +0,0 @@ -#!/bin/bash - -# This script checks the Chip Select (since it's negated it should be put to low value) - -MPU6000_CS_PIN=113 # Corresponds with P9_28 -MPU9250_CS_PIN=49 # Corresponds with P9_28 -MS5611_CS_PIN=7 # Corresponds with P9_42 - -# activate all the GPIOs and force them to untake the bus -echo "Checking MPU6000 CS" -cat /sys/class/gpio/"gpio"$MPU6000_CS_PIN/value - -echo "Cheking MPU9250 CS" -cat /sys/class/gpio/"gpio"$MPU9250_CS_PIN/value - -echo "Checking MS5611 CS" -cat /sys/class/gpio/"gpio"$MS5611_CS_PIN/value diff --git a/Tools/PXF/enable_CS.sh b/Tools/PXF/enable_CS.sh deleted file mode 100644 index 6590332094..0000000000 --- a/Tools/PXF/enable_CS.sh +++ /dev/null @@ -1,59 +0,0 @@ -#!/bin/bash - -# This script enables the Chip Select (since it's negated it should be put to low value) -# of the sensor passed as a parameter - -MPU6000_CS_PIN=113 # Corresponds with P9_28 -MPU9250_CS_PIN=49 # Corresponds with P9_28 -MS5611_CS_PIN=7 # Corresponds with P9_42 - -# activate all the GPIOs and force them to untake the bus -echo "Disabling MPU6000 CS" -echo $MPU6000_CS_PIN > /sys/class/gpio/export 2> /dev/null -echo out > /sys/class/gpio/"gpio"$MPU6000_CS_PIN/direction -echo 1 > /sys/class/gpio/"gpio"$MPU6000_CS_PIN/value - -echo "Disabling MPU9250 CS" -echo $MPU9250_CS_PIN > /sys/class/gpio/export 2> /dev/null -echo out > /sys/class/gpio/"gpio"$MPU9250_CS_PIN/direction -echo 1 > /sys/class/gpio/"gpio"$MPU9250_CS_PIN/value - -echo "Disabling MS5611 CS" -echo $MS5611_CS_PIN > /sys/class/gpio/export 2> /dev/null -echo out > /sys/class/gpio/"gpio"$MS5611_CS_PIN/direction -echo 1 > /sys/class/gpio/"gpio"$MS5611_CS_PIN/value - - -if [ $# -eq 0 ] - then - echo "No arguments supplied. Please provide one of the following sensors: mpu6000, mpu9250, ms5611" - echo " source enable_cs.sh " - return 0 -fi - -if [ $1 == "mpu6000" ] -then - CS_PIN=$MPU6000_CS_PIN - echo out > /sys/class/gpio/"gpio"$CS_PIN/direction - echo 0 > /sys/class/gpio/"gpio"$CS_PIN/value - echo "Enabling MPU6000 CS" -elif [ $1 == "mpu9250" ] -then - CS_PIN=$MPU9250_CS_PIN - echo out > /sys/class/gpio/"gpio"$CS_PIN/direction - echo 0 > /sys/class/gpio/"gpio"$CS_PIN/value - echo "Enabling MPU9250 CS" -elif [ $1 == "ms5611" ] -then - CS_PIN=$MS5611_CS_PIN - echo out > /sys/class/gpio/"gpio"$CS_PIN/direction - echo 0 > /sys/class/gpio/"gpio"$CS_PIN/value - echo "Enabling MS5611 CS" -else - echo "Sensor supplied invaled. Please provide one of the following sensors: mpu6000, mpu9250, ms5611" - echo " source enable_cs.sh " - return 0 -fi - -# to verify do: -# cat /sys/class/gpio/"gpio"$CS_PIN/value