Hi @Jetson-Nano ,
I asked around and we currently do not have an official way to do this. In some tests what we have done is read the RC values from mavlink server and pick a RC channel (a switch), so that when the switch is flipped, you send our the command using voxl-send-neopixel-cmd.c
. Please note that you cannot run the python test script while PX4 is running (which is your use case).
So basically, what is missing is some "glue" that will tie together the RC channel logic with sending out the LED command. Using PX4 for this may be too complicated and it can be done in a simple script. This can be your own app.
I can provide an example of achieving this relatively easily using python:
- using a python script that calls
px4-listener
to get RC data packet into python, you can get all the RC channels and decide what channel you want to use for the LED. I don't have the exact script, but i am pasting another script i recently wrote for logging barometer data in the similar way
- when you decide that an led command needs to be sent out, you can do a system call / subprocess call to
voxl-send-neopixel-cmd
to turn the led on / off. This helper tool already has support to just turn the while led on or off. Note that this command will send a message via MPA pipe to PX4 process, which will forward the data packet to the PX4 ESC driver, and the message will go out via UART to the ESC (so that you understand the data flow)
So your final python script might look something like this (outline):
make sure PX4 is running
- loop and periodically read RC channels (lets say at 5-10hz)
- if there is transition on a RC channel that is mapped to a switch, call
voxl-send-neopixel-cmd
In order to modify the barometer reading script for RC data, you can just first print out what the px4-listener
returns and then parse the RC channel values.
Please let me know if this will work for you, If you need more specific example, I can help but it will take a bit more time (i just wanted to propose a path forward to you).
script for logging barometer data:
import subprocess
import time
import numpy as np
import argparse
# install plotly using pip3 install plotly --upgrade
parser = argparse.ArgumentParser(description='Barometer Test Script')
parser.add_argument('-n','--num-samples', type=int, required=False, default=1000)
args = parser.parse_args()
max_sample_count = args.num_samples
def get_px4_baro():
cmd = 'px4-listener sensor_baro'
p = subprocess.Popen(cmd, shell=True, stdout=subprocess.PIPE, stderr=subprocess.STDOUT)
timestamp = None
pressure = None
temperature = None
for line in p.stdout.readlines():
l=str(line)
#print(l)
if 'timestamp' in l:
ll = l.split(':')[1].split()[0]
timestamp = float(ll)
if 'pressure' in l:
ll = l.split(':')[-1][:-3]
pressure = float(ll)
if 'temperature' in l:
ll = l.split(':')[-1][:-3]
temperature = float(ll)
retval = p.wait()
return (timestamp,pressure,temperature)
tlast = 0
ts = []
ps = []
temps = []
sample_count = 0
while (sample_count < max_sample_count):
(timestamp, pressure, temperature) = get_px4_baro()
#make sure we got new data
if timestamp != tlast:
sample_count += 1
ts.append(timestamp)
ps.append(pressure)
temps.append(temperature)
print(f'({sample_count})[{timestamp}] P: {pressure}, T: {temperature}')
tlast=timestamp
time.sleep(0.01)
print('Finished collecting data')
print('Generating plots..')
try:
import plotly.graph_objects as go
from plotly.subplots import make_subplots
except:
print('WARNING: In order to plot the results, install the Python "plotly" module: pip3 install plotly --upgrade')
sys.exit(0)
fig = make_subplots(rows=3, cols=1, start_cell="top-left")
ts_plot = np.array(ts)
ts_plot -= ts_plot[0]
ts_plot *= 0.000001 #convert from us to s
# calculate approximate height from start
dh = np.array(ps)
dh -= dh[0] # subtract the first value
dh /= 12.0 # about 12 Pascals per meter at standard pressure and temperature
fig.add_trace(go.Scatter(x=ts_plot, y=np.array(ps), name='Pressure (Pa)'), row=1, col=1)
fig.add_trace(go.Scatter(x=ts_plot, y=np.array(temps), name='Temperature (deg C)'), row=2, col=1)
fig.add_trace(go.Scatter(x=ts_plot, y=dh, name='Approx Height (m)'), row=3, col=1)
fig.update_layout(title_text='Barometer Test Results')
fig.update_xaxes(title_text='Time (s)',row=1, col=1)
fig.update_yaxes(title_text='Pressure (Pa)',row=1, col=1)
fig.update_xaxes(title_text='Time (s)',row=2, col=1)
fig.update_yaxes(title_text='Temperature (deg C)',row=2, col=1)
fig.update_xaxes(title_text='Time (s)',row=3, col=1)
fig.update_yaxes(title_text='Approx Height (m)',row=3, col=1)
fig.update_xaxes(matches='x')
fig.write_html('barometer_test_results.html',include_plotlyjs='cdn')
#fig.show() #the figure will not show on VOXL because there is no display / browser
print('done')