I’m working on a project where I use QGroundControl to upload missions in Mission mode, and I want to access the waypoints (mission items) directly from PX4, as I have a custom guidance algorithm running on a companion computer.
The idea is to:
Use QGC to define/upload waypoints
Read those waypoints inside PX4 (from MAVLink or internal mission storage)
Send them to my companion computer (via MAVLink or other interface) to process using my own guidance logic
My Questions:
What is the best way to access the mission waypoints from PX4 firmware? Is there a uORB topic or API that I can tap into?
Where in the PX4 source code is the mission data stored after uploading from QGC?
Details of the hardware:
Autopilot: Pixhawk 6x with firmware version v1.16.alpha
Companion computer: Raspberry Pi 4B running Ubuntu 24.04
Connected using an Ethernet cable
Extract mission waypoints
In this tuto, I implement the code in examples/px4_simple_app.cpp for displaying waypoints created in QGC and send to vehicle. This example displays only the latitude waypoints.
1) change the file extension to .cpp and
modif extern "C" __EXPORT int px4_simple_app_main(int argc, char *argv[]);
to avoid error:unknown type name ‘namespace’ [https://stackoverflow.com/questions/13602249/how-to-fix-error-unknown-type-name-namespace]
2) includes :
#include <dataman_client/DatamanClient.hpp>
#include <navigator/navigator.h>
#include <uORB/topics/mission.h>
3) subscribe to mission topic :
/* subscribe to mission topic */
uORB::Subscription _mission_sub{ORB_ID(mission)};
4) code to extract wps :
/**
* @brief Maximum time to wait for dataman loading
*
*/
static constexpr hrt_abstime MAX_DATAMAN_LOAD_WAIT{500_ms};
if (_mission_sub.updated()) {
mission_s new_mission;
_mission_sub.update(&new_mission);
PX4_INFO("new_mission.count: %d", (int)new_mission.count);
DatamanCache _dataman_cache{"mission_dm_cache_miss", 10}; /**< Dataman cache of mission items*/
for (int i = 0; i <= new_mission.count; i++) {
mission_item_s next_position_mission_item;
const dm_item_t mission_dataman_id = static_cast<dm_item_t>(new_mission.mission_dataman_id);
bool success = _dataman_cache.loadWait(mission_dataman_id, i,
reinterpret_cast<uint8_t *>(&next_position_mission_item), sizeof(next_position_mission_item), MAX_DATAMAN_LOAD_WAIT);
if (success) { // retrieve wps here
PX4_INFO("Position lat %.6f\t", next_position_mission_item.lat);
}
}
}
5) add to CmakeLists.txt :
DEPENDS
dataman_client
6) select this px4_simple_app in boardconfig, compile with make px4_sitl gazebo. In the mavlink console call the app with px4_simple_app.