mirror of https://github.com/ArduPilot/ardupilot
Tools: remove unused Linux scripts/sources
This commit is contained in:
parent
f7ac6c8d86
commit
524b0870ff
|
@ -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
|
||||
|
|
@ -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 <victor@erlerobot.com>
|
||||
|
||||
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 <sensor> "
|
||||
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 <sensor> "
|
||||
return 0
|
||||
fi
|
||||
|
|
@ -1,55 +0,0 @@
|
|||
#include <stdio.h>
|
||||
#include <sys/time.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <sys/mman.h>
|
||||
#include <sys/stat.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#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();
|
||||
}
|
||||
}
|
|
@ -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
|
|
@ -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 <sensor> "
|
||||
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 <sensor> "
|
||||
return 0
|
||||
fi
|
||||
|
||||
# to verify do:
|
||||
# cat /sys/class/gpio/"gpio"$CS_PIN/value
|
Loading…
Reference in New Issue