Create a new pipe to publish barometer data for VOXL 2
-
I see that in the list of
voxl-inspect-services
, there isn't a service to read barometer data. It looks like the only ways to read the data from the onboard barometer on the VOXL 2 is to either use the PX4 Flight controller or the I2C address given in the page on onboard sensors (https://docs.modalai.com/voxl2-onboard-sensors/). I ultimately want to create a python script that listens to the barometer data.How do I create a new pipe using MPA that publishes barometer data?
-
@svempati , both barometers are connected to the DSP inside VOXL2, not the CPU, so they cannot be accessed directly from CPU. PX4 has to be running in order to get the data. PX4 currently uses one barometer.
I am not sure what the easiest way to the barometer data into python is.. maybe using mavlink (pymavlink).
Once px4 is running, you can use a tool
px4-listener
to print out topics, for example:voxl2:~$ px4-listener sensor_baro TOPIC: sensor_baro sensor_baro timestamp: 4249427578 (0.104230 seconds ago) timestamp_sample: 4249426507 (1071 us before timestamp) device_id: 12018473 (Type: 0xB7, I2C:5 (0x63)) pressure: 99824.01562 temperature: 31.20201 error_count: 0
If you just need a python script that listens to barometer data, you can call
px4-listener
from python and get the results. I am going to add this example in case there is no other good way of doing this for now (others please feel free to post a better way!)create a new file :
get_px4_baro.py
:import subprocess import time 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 for i in range(1000): (timestamp, pressure, temperature) = get_px4_baro() #make sure we got new data if timestamp != tlast: print(f'[{timestamp}] P: {pressure}, T: {temperature}') tlast=timestamp time.sleep(0.01)
run it:
voxl2:~$ python3 get_px4_baro.py [4421232495.0] P: 99825.92188, T: 31.22604 [4421359025.0] P: 99826.1875, T: 31.22871 [4421485636.0] P: 99825.9375, T: 31.22871 [4421612204.0] P: 99825.39062, T: 31.22337
The script assumes that px4 is already running and
px4-listener sensor_baro
returns proper results..In principle, this approach can be used to get any data from px4, which is accessible using
px4-listener
. This is an example and it does not have robust error checking in the script, so please treat it accordingly. It may be useful to get started with looking at the data while looking for a better solution.Alex
-
@Alex-Kushleyev Thank you for your response, I will try that out. I have a follow up question, is there a way to make a pipe from the px4 listener that will be running in the background?
-
It looks like our libmodal pipe library does not define a type for publishing a barometer message, which would be here https://gitlab.com/voxl-public/voxl-sdk/core-libs/libmodal-pipe/-/blob/dev/library/include/modal_pipe_interfaces.h , just like camera, imu data types.
Unfortunately without the definition of this data type, you could not publish the barometer data via mpa.
If you provide a bit more information about what you are trying to achieve, perhaps i can suggest a workaround.
Alex
-
@Alex-Kushleyev So what I wanted to ask was whether you could pipe px4 messages in general into mpa. The idea is I would like to do something like this:
px4-listener sensor_baro -> some measurements -> Get pressure measurement -> store to mpa -> read mpa pipe from python
Would it be possible to create a pipeline that looks something like this?
-
@svempati , you cannot send arbitrary messages to mpa - the message has to be defined in the header file in order to be supported.
When you say "store to mpa" - what exactly do you mean? store to a log file?
Using the script i provided you can get the data directly into python3 - do you still need the steps in between?
Alex
-
@Alex-Kushleyev By storing to mpa I mean creating a new service under
voxl-inspect-services
and storing px4 messages under that new service.I understood that
px4-listener
could be directly executed in python3, but I was assuming that listening to data from one of the voxl-services would be the a faster or more efficient way to get data on the VOXL board.Sashank
-
@svempati , if we are going to officially add a service to provide the baro data via MPA, we would not do it the way i described because this approach is kind of a "hack" which can be used for some quick testing in absence of other alternatives.
The proper way would be to have the PX4 service (or another related service) publish the message directly from PX4 (and not use the listener in the middle). However, this does not exist right now and we have not yet planned to add it. That is why I provided a way for you to work around this issue which can potentially unblock you.
Meanwhile, I will discuss with the team how / when we could enable the official support for this data in a service.
Alex
-
@Alex-Kushleyev Got it. Thank you your help and for taking the time to answer my questions!
Sashank