ESC Telemetry Remains Uninitialized on M300 (Firmware v09.00.0503, ROS Kinetic, OSDK-ROS 4.1 / OSDK 4.1)
Hello DJI Developers,
I'm encountering an issue with ESC telemetry on my DJI Matrice 300 running firmware v09.00.0503. I am using ROS Kinetic, Onboard-SDK-ROS 4.1, and Onboard-SDK 4.1. I have attempted to add ESC telemetry (TOPIC_ESC_DATA) to the ROS wrapper based on Issue [#299](https://github.com/dji-sdk/Onboard-SDK-ROS/issues/299) and related discussions, but the ESC data remains uninitialized, and the node dies with an error.
Steps I Have Taken
1. Creating a Custom ESC Message
-
Message File:
I createdESCStatus.msgin themsgfolder (e.g.,dji_osdk_ros/msg/ESCStatus.msg). -
Message Definition:
My message contains fields for ESC telemetry (using fixed-size arrays for 8 ESCs):std_msgs/Header header int32[8] speed # Motor speeds for each ESC int32[8] current # Motor currents (mA) float32[8] voltage # Motor voltages (V) int32[8] temperature # Temperature (deg Celsius) bool[8] stall # Stall flags bool[8] empty # Empty flags bool[8] unbalanced # Unbalanced flags bool[8] escDisconnected # Disconnected flags bool[8] temperatureHigh # High temperature flags int32[8] reserved # Reserved for future use -
Build Confirmation:
The build output shows thatESCStatus.msgwas successfully generated for multiple languages (Python, C++, etc.).
2. Modifying the ROS Wrapper
a. Header File Modifications (dji_sdk_node.h)
- I added the following include:
#include <dji_osdk_ros/ESCStatus.h> - I declared a new publisher:
ros::Publisher esc_publisher;
b. Adding the ESC Topic to the 50Hz Subscription (dji_sdk_node.cpp)
- In the function
initDataSubscribeFromFC(ros::NodeHandle& nh), I modified the topic list for the 50Hz package. I inserted:// Existing topics... topicList50Hz.push_back(Telemetry::TOPIC_RC); topicList50Hz.push_back(Telemetry::TOPIC_ESC_DATA); // Added ESC telemetry topic topicList50Hz.push_back(Telemetry::TOPIC_VELOCITY); topicList50Hz.push_back(Telemetry::TOPIC_GPS_CONTROL_LEVEL);
c. Initializing the ESC Publisher (dji_sdk_node.cpp, initPublisher)
- In the
initPublisher(ros::NodeHandle& nh)function, I added:esc_publisher = nh.advertise<dji_osdk_ros::ESCStatus>("dji_sdk/esc", 10);
d. Modifying the Publisher Code (dji_sdk_node_publisher.cpp)
- In the
publish50HzData()function, I added the following code to retrieve and publish ESC telemetry:// Retrieve ESC telemetry data Telemetry::TypeMap<Telemetry::TOPIC_ESC_DATA>::type esc_data = vehicle->subscribe->getValue<Telemetry::TOPIC_ESC_DATA>(); // Check if ESC data appears to be initialized by verifying key fields if (esc_data.esc[0].speed != 0 || esc_data.esc[0].current != 0) { dji_osdk_ros::ESCStatus esc_status; esc_status.header.stamp = ros::Time::now(); // Loop through expected ESCs (for M300, typically 4 ESCs are active) for (int i = 0; i < 4; i++) { esc_status.speed[i] = esc_data.esc[i].speed; esc_status.current[i] = esc_data.esc[i].current; esc_status.voltage[i] = esc_data.esc[i].voltage; esc_status.temperature[i] = esc_data.esc[i].temperature; esc_status.stall[i] = esc_data.esc[i].stall; esc_status.empty[i] = esc_data.esc[i].empty; esc_status.unbalanced[i] = esc_data.esc[i].unbalanced; esc_status.escDisconnected[i] = esc_data.esc[i].escDisconnected; esc_status.temperatureHigh[i] = esc_data.esc[i].temperatureHigh; esc_status.reserved[i] = esc_data.esc[i].reserved; } p->esc_publisher.publish(esc_status); } else { ROS_WARN("ESC data not initialized!"); }
3. Building and Testing
- I rebuilt the workspace with:
cd ~/catkin_ws catkin_make source devel/setup.bash - When launching the node, I see that the 50Hz package starts with 13 topics. However, I get the following error:
and the node dies.ERRORLOG/1 @ getValue, L352: Topic 0x25 value memory not initialized, return default [FATAL] ... Call to publish() on an invalid Publisher
4. Issue Encountered and My Questions
Even after these modifications, the ESC telemetry data remains uninitialized. Based on my research and previous discussions in issues like [#299](https://github.com/dji-sdk/Onboard-SDK-ROS/issues/299), I suspect that:
- The M300 firmware (v09.00.0503) with OSDK 4.1 might not support ESC telemetry.
- The flight controller may not populate TOPIC_ESC_DATA, causing the error and leading to an invalid publisher call.
My Questions Are:
- Is ESC telemetry (TOPIC_ESC_DATA) supported on the M300 with firmware v09.00.0503 using OSDK 4.1 / OSDK-ROS 4.1?
- If supported, are there additional configuration steps (e.g., via DJI Assistant 2 or additional SDK calls) required to enable ESC telemetry on the M300?
- Are there any known workarounds for the “memory not initialized” error for TOPIC_ESC_DATA on this platform?
Any guidance, documentation updates, or workaround suggestions would be greatly appreciated.
Thank you very much for your time and assistance.
Agent comment from Leon in Zendesk ticket #134878:
Hello, thank you for your patience. We have confirmed that the M300 model supports ESC data subscription, so we are more inclined to believe that it may be a problem with the usage method or operation steps that caused you to fail to obtain the data. We have provided a code example in the Linux telemetry sample, which may provide you with a reference for the steps: https://github.com/dji-sdk/Onboard-SDK/blob/master/sample/platform/linux/telemetry/telemetry_sample.cpp#L330
°°°
I have listed all the steps above, could you tell me what am I doing wrong?
My question is, in simulation mode, when connected to a laptop (DJI Assistant), is ESC topic accessible in HITL?
Agent comment from Leon in Zendesk ticket #134878:
Hello, sorry, due to the recent engineer vacation, our response time has decreased. It is not supported in the simulator. We recommend that you subscribe in the actual flight environment.
°°°
so, I connected the drone and armed it, but I am still topic is not being published?