Telemetry Data Not Accurate

When modifying the example telemetry_py service to collect more telemetry data such as pitch/yaw/roll/altitude, I am able to get it running but it does not seem like altitude is updating and when logged, never changes from 0.0

async def service_main():
    # Initialisation code
    ulog.setup_logging(PROCESS_NAME)
    logger = logging.getLogger("main")
    run = True
    def sig_handler(*_):
        nonlocal run
        run = False

    loop = asyncio.get_running_loop()
    loop.add_signal_handler(signal.SIGTERM, sig_handler)

    # Setup Consumer
    consumer = telemetry_binding.Consumer("/dev/shm")

    # Setup Sensors
    pressure = telemetry_binding.types.float32_t(0.0)
    temperature = telemetry_binding.types.array_float32_t(0.0, 10)
    altitude = telemetry_binding.types.float32_t(0.0)
    drone_attitude = telemetry_binding.types.array_float32_t(0.0, 4)
    camera_attitude = telemetry_binding.types.array_float32_t(0.0, 4)

    consumer.reg(pressure, "sensors_barometer.pressure")
    consumer.reg(temperature, "sensors_imu.temperature")
    consumer.reg(altitude, "flight_controller.altitude_agl")
    consumer.reg(drone_attitude, "attitude_ned_q")
    consumer.reg(camera_attitude, "fcam@eis@video.view_ned_start_q")
    consumer.regComplete()

    # Loop Code
    while run:
        consumer.getSample(
            telemetry_binding.types.timespec(0, 0),
            telemetry_binding.Method.Latest,
        )

        PATH_GUIDANCE = "/mnt/user-internal/missions-data/com.parrot.missions.samples.telemetry_py/telemetry_service.txt" #new
        with open(PATH_GUIDANCE, 'a') as file:#new
            file.write(f"Telemetry Data:\n")
            file.write(f"Pressure: {pressure}\n")#new
            file.write(f"Temperature: {temperature[0]}\n")#new
            file.write(f"Altitude: {altitude}\n")
            file.write(f"Drone Orientation: {drone_attitude[0]:.10f}, Yaw: {drone_attitude[1]:.10f}, Roll: {drone_attitude[10]:.10f}\n")
            file.write(f"Camera Orientation: {camera_attitude[0]:.10f}, Yaw: {camera_attitude[1]:.10f}, Roll: {camera_attitude[10]:.10f}\n")
            file.write("------------------------------------------------\n")

        await asyncio.sleep(5)

Am I doing something wrong in the service? Do these telemetry points not update unless the drone is in flying mode or something along those lines? Help appreciated.

HI @kaeladair,

I think you register the wrong value.

consumer.reg(altitude, "flight_controller.altitude_agl")
consumer.reg(drone_attitude, "attitude_ned_q")
  • flight_controller is not a correct section name. The correct section name is drone_controller.

  • the name of the section is missing (drone_controller)

Here are the corrected lines:

consumer.reg(altitude, "drone_controller.altitude_agl")
consumer.reg(drone_attitude, "drone_controller.attitude_ned_q")

As a reminder, to obtain values from telemetry, you need to enter the full name of the data (section_name + data_name). All data available in telemetry can be found in this documentation.

I fixed the errors and I am still getting the same result. Here is my full service code:

import asyncio
import logging
import signal
import ulog
import telemetry_binding

# This is limited to 15 charecters
PROCESS_NAME = b"ex_tlm_py"

async def service_main():
    # Initialisation code
    ulog.setup_logging(PROCESS_NAME)
    logger = logging.getLogger("main")
    run = True
    def sig_handler(*_):
        nonlocal run
        run = False

    loop = asyncio.get_running_loop()
    loop.add_signal_handler(signal.SIGTERM, sig_handler)

    # Setup Consumer
    consumer = telemetry_binding.Consumer("/dev/shm")

    # Setup Sensors
    pressure = telemetry_binding.types.float32_t(0.0)
    temperature = telemetry_binding.types.array_float32_t(0.0, 10)
    altitude = telemetry_binding.types.float32_t(0.0)
    drone_attitude = telemetry_binding.types.array_float32_t(0.0, 4)
    camera_attitude = telemetry_binding.types.array_float32_t(0.0, 4)

    consumer.reg(pressure, "sensors_barometer.pressure")
    consumer.reg(temperature, "sensors_imu.temperature")
    consumer.reg(altitude, "drone_controller.altitude_agl")
    consumer.reg(drone_attitude, "drone_controller.attitude_ned_q")
    consumer.reg(camera_attitude, "fcam@eis@video.view_ned_start_q")
    consumer.regComplete()

    # Loop Code
    while run:
        consumer.getSample(
            telemetry_binding.types.timespec(0, 0),
            telemetry_binding.Method.Latest,
        )

        PATH_GUIDANCE = "/mnt/user-internal/missions-data/com.parrot.missions.samples.telemetry_py/telemetry_service.txt" #new
        with open(PATH_GUIDANCE, 'a') as file:#new
            file.write(f"Telemetry Data:\n")
            file.write(f"Pressure: {pressure}\n")#new
            file.write(f"Temperature: {temperature[0]}\n")#new
            file.write(f"Altitude: {altitude}\n")
            file.write(f"Drone Orientation: {drone_attitude[0]:.10f}, Yaw: {drone_attitude[1]:.10f}, Roll: {drone_attitude[10]:.10f}\n")
            file.write(f"Camera Orientation: {camera_attitude[0]:.10f}, Yaw: {camera_attitude[1]:.10f}, Roll: {camera_attitude[10]:.10f}\n")
            file.write("------------------------------------------------\n")

        await asyncio.sleep(5)

    # Cleanup code
    logger.info("Cleaning up")
    consumer = None

    return 0


def main():
    asyncio.run(service_main())

And here is the script for running the service with olympe (just the service, empty mission):

import logging
import olympe
import olympe.log
import os
from olympe.messages import mission

DRONE_IP = os.environ.get("DRONE_IP", "192.168.42.1")
# hello mission
# telemetry test mission
HELLO_MISSION_URL = os.environ.get("HELLO_MISSION_URL", "/home/intemnets-lab/kael/airsdk-samples/telemetry_py/.airsdk/out/telemetry_py-classic/images/com.parrot.missions.samples.telemetry_py.tar.gz")

olympe.log.update_config({"loggers": {"olympe": {"level": "WARNING"}}})
logger = logging.getLogger("olympe")


def test_hello_mission():
    drone = olympe.Drone(DRONE_IP)
    with drone.mission.from_path(HELLO_MISSION_URL).open() as m:

        assert drone.connect()
        mission_activated = drone(
            mission.load(uid=m.uid)
            >> mission.activate(uid=m.uid)
        )
        assert mission_activated.wait(), mission_activated.explain()

        input("Press to stop...")
        
        assert drone.disconnect()

if __name__ == "__main__":
    test_hello_mission()

And here is the output I’m getting:

The pitch/yaw/roll is not correctly calculated yet but I don’t think the output should be 0.00000 …

Hi @kaeladair,

drone_controller.attitude_ned_q and fcam@eis@video.view_ned_start_q are not arrays (in the documentation, the [] is not present). So, to get these value, you need to register data separately with python:

consumer.reg(drone_attitude_w, "drone_controller.attitude_ned_q.w")
consumer.reg(drone_attitude_x, "drone_controller.attitude_ned_q.x")
consumer.reg(drone_attitude_y, "drone_controller.attitude_ned_q.y")
consumer.reg(drone_attitude_z, "drone_controller.attitude_ned_q.z")

Regards,
Axel

This topic was automatically closed after 30 days. New replies are no longer allowed.