Skip to content

Commit

Permalink
bunch of updates trying to get mavlink collection online
Browse files Browse the repository at this point in the history
  • Loading branch information
misko committed Mar 6, 2024
1 parent f555ab1 commit ef880ab
Show file tree
Hide file tree
Showing 12 changed files with 530 additions and 97 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -18,3 +18,4 @@ test_data.txt
**/tmp_*
*.tmp
**/*.tmp
**/mav.*
4 changes: 3 additions & 1 deletion data_collection_model_and_results/rover/rover_v3.1/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -136,4 +136,6 @@ See [here](https://www.dropbox.com/s/egpfn434aox6vvk/roverv3_3dparts.zip?dl=0)

[Low power disconnect](https://www.dropbox.com/scl/fi/wmjql1251xnxs90oqn2jd/lower_power_disconnect_30A.pdf?rlkey=h3vitle22f5xrkcthws3yf8ft&dl=0)

[Cytron Smart duo 30](https://www.dropbox.com/scl/fi/eeqg87gi8wzy2aa1k1yx3/MDDS30_User_Manual.pdf?rlkey=xe49gu88bpqspxbg2dh6x139w&dl=0)
[Cytron Smart duo 30](https://www.dropbox.com/scl/fi/eeqg87gi8wzy2aa1k1yx3/MDDS30_User_Manual.pdf?rlkey=xe49gu88bpqspxbg2dh6x139w&dl=0)

[Fans](https://www.dropbox.com/s/b4bna0s1yyfwyqa/cooler_guys_fan.pdf?dl=0)
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ rover_id=$1
echo ${rover_id} > ~/rover_id

sudo apt-get update
sudo apt-get install git screen libiio-dev libiio-utils vim -y
sudo apt-get install git screen libiio-dev libiio-utils vim python3-dev -y

# virtual enviornment setup
python -m venv ~/spf-virtualenv
Expand Down
1 change: 1 addition & 0 deletions requirements.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ pytest==7.4.3
python-dateutil==2.8.2
PyYAML==6.0.1
requests==2.31.0
RPi.GPIO==0.7.1
scipy==1.11.4
shapely==2.0.2
six==1.16.0
Expand Down
124 changes: 124 additions & 0 deletions spf/data_collector.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,124 @@
import logging
import sys
import time

import numpy as np

from spf.sdrpluto.sdr_controller import (
EmitterConfig,
ReceiverConfig,
get_pplus,
setup_rx,
setup_rxtx,
)
from spf.wall_array_v2 import v2_column_names


class DataCollector:
def __init__(self, yaml_config, filename_npy, tag=""):
self.yaml_config = yaml_config
self.filename_npy = filename_npy
self.record_matrix = None

def radios_to_online(self):
# record matrix
column_names = v2_column_names(nthetas=self.yaml_config["n-thetas"])
if not self.yaml_config["dry-run"]:
self.record_matrix = np.memmap(
self.filename_npy,
dtype="float32",
mode="w+",
shape=(
2, # TODO should be nreceivers
self.yaml_config["n-records-per-receiver"],
len(column_names),
), # t,tx,ty,rx,ry,rtheta,rspacing / avg1,avg2 / sds
)

# lets open all the radios
radio_uris = []
if self.yaml_config["emitter"]["type"] == "sdr":
radio_uris.append(self.yaml_config["emitter"]["receiver-uri"])
for receiver in self.yaml_config["receivers"]:
radio_uris.append(receiver["receiver-uri"])
for radio_uri in radio_uris:
get_pplus(uri=radio_uri)

time.sleep(0.1)

target_yaml_config = self.yaml_config["emitter"]
if target_yaml_config["type"] == "sdr": # this wont be the case for mavlink
# setup the emitter
target_rx_config = ReceiverConfig(
lo=target_yaml_config["f-carrier"],
rf_bandwidth=target_yaml_config["bandwidth"],
sample_rate=target_yaml_config["f-sampling"],
gains=[target_yaml_config["rx-gain"], target_yaml_config["rx-gain"]],
gain_control_modes=[
target_yaml_config["rx-gain-mode"],
target_yaml_config["rx-gain-mode"],
],
enabled_channels=[0, 1],
buffer_size=target_yaml_config["buffer-size"],
intermediate=target_yaml_config["f-intermediate"],
uri=target_yaml_config["receiver-uri"],
)
target_tx_config = EmitterConfig(
lo=target_yaml_config["f-carrier"],
rf_bandwidth=target_yaml_config["bandwidth"],
sample_rate=target_yaml_config["f-sampling"],
intermediate=target_yaml_config["f-intermediate"],
gains=[target_yaml_config["tx-gain"], -80],
enabled_channels=[0],
cyclic=True,
uri=target_yaml_config["emitter-uri"],
motor_channel=target_yaml_config["motor_channel"],
)

pplus_rx, _ = setup_rxtx(
rx_config=target_rx_config, tx_config=target_tx_config, leave_tx_on=True
)
pplus_rx.close_rx()

# get radios online
receiver_pplus = {}
for receiver in self.yaml_config["receivers"]:
rx_config = ReceiverConfig(
lo=receiver["f-carrier"],
rf_bandwidth=receiver["bandwidth"],
sample_rate=receiver["f-sampling"],
gains=[receiver["rx-gain"], receiver["rx-gain"]],
gain_control_modes=[
receiver["rx-gain-mode"],
receiver["rx-gain-mode"],
],
enabled_channels=[0, 1],
buffer_size=receiver["buffer-size"],
intermediate=receiver["f-intermediate"],
uri=receiver["receiver-uri"],
rx_spacing=receiver["antenna-spacing-m"],
rx_theta_in_pis=receiver["theta-in-pis"],
motor_channel=receiver["motor_channel"],
rx_buffers=receiver["rx-buffers"],
)
assert "emitter-uri" not in receiver
assert (
"skip_phase_calibration" not in self.yaml_config
or self.yaml_config["skip_phase_calibration"]
)
# there is no emitter to setup, its already blasting
pplus_rx = setup_rx(rx_config=rx_config)

if pplus_rx is None:
logging.info("Failed to bring RXTX online, shuttingdown")
sys.exit(1)
else:
logging.debug("RX online!")
receiver_pplus[pplus_rx.uri] = pplus_rx
assert pplus_rx.rx_config.rx_pos is not None

def start(self):
pass

def is_collecting(self):
pass
2 changes: 2 additions & 0 deletions spf/device_mapping
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
1 10
2 30
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,13 @@
import threading
import time

import RPi.GPIO as GPIO
try:
import RPi.GPIO as GPIO
except ImportError:
pass


class UtrasonicDistanceController:
class DistanceFinderController:
def __init__(self, trigger=2, echo=3):
# assign pins
self.trigger = trigger
Expand All @@ -18,6 +21,9 @@ def __init__(self, trigger=2, echo=3):
GPIO.setup(self.trigger, GPIO.OUT)
GPIO.setup(self.echo, GPIO.IN)

def run_in_new_thread(self):
threading.Thread(target=self.run, daemon=True).start()

def run(self, sample_interval=0.05):
# start sensor
GPIO.output(self.trigger, GPIO.LOW)
Expand Down Expand Up @@ -51,8 +57,8 @@ def run(self, sample_interval=0.05):

args = parser.parse_args()

udc = UtrasonicDistanceController(trigger=args.trigger, echo=args.echo)
threading.Thread(target=udc.run, daemon=True).start()
udc = DistanceFinderController(trigger=args.trigger, echo=args.echo)
udc.run_in_new_thread()
for x in range(15 * 2):
time.sleep(1.0 / 2)
print(udc.distance)
Expand Down
Loading

0 comments on commit ef880ab

Please sign in to comment.