mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-22 22:32:11 +08:00
Add support for mavlink message DEBUG
This commit is contained in:
committed by
Nuno Marques
parent
b6c30cf9b2
commit
eeb966d375
@@ -47,6 +47,7 @@ set(msg_file_names
|
||||
control_state.msg
|
||||
cpuload.msg
|
||||
debug_key_value.msg
|
||||
debug_value.msg
|
||||
differential_pressure.msg
|
||||
distance_sensor.msg
|
||||
ekf2_innovations.msg
|
||||
|
||||
@@ -0,0 +1,3 @@
|
||||
uint32 timestamp_ms # in milliseconds since system start
|
||||
int8 ind # index of debug variable
|
||||
float32 value # the value to send as debug output
|
||||
@@ -2045,6 +2045,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
configure_stream("ATTITUDE_TARGET", 2.0f);
|
||||
configure_stream("HOME_POSITION", 0.5f);
|
||||
configure_stream("NAMED_VALUE_FLOAT", 1.0f);
|
||||
configure_stream("DEBUG", 1.0f);
|
||||
configure_stream("VFR_HUD", 4.0f);
|
||||
configure_stream("WIND_COV", 1.0f);
|
||||
configure_stream("CAMERA_IMAGE_CAPTURED");
|
||||
@@ -2073,6 +2074,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
configure_stream("ATTITUDE_TARGET", 10.0f);
|
||||
configure_stream("HOME_POSITION", 0.5f);
|
||||
configure_stream("NAMED_VALUE_FLOAT", 10.0f);
|
||||
configure_stream("DEBUG", 10.0f);
|
||||
configure_stream("VFR_HUD", 10.0f);
|
||||
configure_stream("WIND_COV", 10.0f);
|
||||
configure_stream("POSITION_TARGET_LOCAL_NED", 10.0f);
|
||||
@@ -2132,6 +2134,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
configure_stream("ATTITUDE_TARGET", 8.0f);
|
||||
configure_stream("HOME_POSITION", 0.5f);
|
||||
configure_stream("NAMED_VALUE_FLOAT", 50.0f);
|
||||
configure_stream("DEBUG", 50.0f);
|
||||
configure_stream("VFR_HUD", 20.0f);
|
||||
configure_stream("WIND_COV", 10.0f);
|
||||
configure_stream("CAMERA_TRIGGER");
|
||||
|
||||
@@ -65,6 +65,7 @@
|
||||
#include <uORB/topics/camera_capture.h>
|
||||
#include <uORB/topics/cpuload.h>
|
||||
#include <uORB/topics/debug_key_value.h>
|
||||
#include <uORB/topics/debug_value.h>
|
||||
#include <uORB/topics/differential_pressure.h>
|
||||
#include <uORB/topics/distance_sensor.h>
|
||||
#include <uORB/topics/estimator_status.h>
|
||||
@@ -3171,6 +3172,69 @@ protected:
|
||||
}
|
||||
};
|
||||
|
||||
class MavlinkStreamDebug : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
const char *get_name() const
|
||||
{
|
||||
return MavlinkStreamDebug::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
{
|
||||
return "DEBUG";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_DEBUG;
|
||||
}
|
||||
|
||||
uint16_t get_id()
|
||||
{
|
||||
return get_id_static();
|
||||
}
|
||||
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink)
|
||||
{
|
||||
return new MavlinkStreamDebug(mavlink);
|
||||
}
|
||||
|
||||
unsigned get_size()
|
||||
{
|
||||
return (_debug_time > 0) ? MAVLINK_MSG_ID_DEBUG_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0;
|
||||
}
|
||||
|
||||
private:
|
||||
MavlinkOrbSubscription *_debug_sub;
|
||||
uint64_t _debug_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamDebug(MavlinkStreamDebug &);
|
||||
MavlinkStreamDebug &operator = (const MavlinkStreamDebug &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamDebug(Mavlink *mavlink) : MavlinkStream(mavlink),
|
||||
_debug_sub(_mavlink->add_orb_subscription(ORB_ID(debug_value))),
|
||||
_debug_time(0)
|
||||
{}
|
||||
|
||||
void send(const hrt_abstime t)
|
||||
{
|
||||
struct debug_value_s debug = {};
|
||||
|
||||
if (_debug_sub->update(&_debug_time, &debug)) {
|
||||
mavlink_debug_t msg = {};
|
||||
|
||||
msg.time_boot_ms = debug.timestamp_ms;
|
||||
msg.ind = debug.ind;
|
||||
msg.value = debug.value;
|
||||
|
||||
mavlink_msg_debug_send_struct(_mavlink->get_channel(), &msg);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
class MavlinkStreamNavControllerOutput : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
@@ -4168,6 +4232,7 @@ const StreamListItem *streams_list[] = {
|
||||
new StreamListItem(&MavlinkStreamActuatorControlTarget<2>::new_instance, &MavlinkStreamActuatorControlTarget<2>::get_name_static, &MavlinkStreamActuatorControlTarget<2>::get_id_static),
|
||||
new StreamListItem(&MavlinkStreamActuatorControlTarget<3>::new_instance, &MavlinkStreamActuatorControlTarget<3>::get_name_static, &MavlinkStreamActuatorControlTarget<3>::get_id_static),
|
||||
new StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static, &MavlinkStreamNamedValueFloat::get_id_static),
|
||||
new StreamListItem(&MavlinkStreamDebug::new_instance, &MavlinkStreamDebug::get_name_static, &MavlinkStreamDebug::get_id_static),
|
||||
new StreamListItem(&MavlinkStreamNavControllerOutput::new_instance, &MavlinkStreamNavControllerOutput::get_name_static, &MavlinkStreamNavControllerOutput::get_id_static),
|
||||
new StreamListItem(&MavlinkStreamCameraCapture::new_instance, &MavlinkStreamCameraCapture::get_name_static, &MavlinkStreamCameraCapture::get_id_static),
|
||||
new StreamListItem(&MavlinkStreamCameraTrigger::new_instance, &MavlinkStreamCameraTrigger::get_name_static, &MavlinkStreamCameraTrigger::get_id_static),
|
||||
|
||||
@@ -138,6 +138,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
|
||||
_collision_report_pub(nullptr),
|
||||
_control_state_pub(nullptr),
|
||||
_debug_key_value_pub(nullptr),
|
||||
_debug_value_pub(nullptr),
|
||||
_gps_inject_data_pub(nullptr),
|
||||
_command_ack_pub(nullptr),
|
||||
_control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))),
|
||||
@@ -312,6 +313,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
|
||||
handle_message_named_value_float(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_DEBUG:
|
||||
handle_message_debug(msg);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
@@ -2384,6 +2389,26 @@ void MavlinkReceiver::handle_message_named_value_float(mavlink_message_t *msg)
|
||||
}
|
||||
}
|
||||
|
||||
void MavlinkReceiver::handle_message_debug(mavlink_message_t *msg)
|
||||
{
|
||||
mavlink_debug_t debug_msg;
|
||||
debug_value_s debug_topic = {};
|
||||
|
||||
mavlink_msg_debug_decode(msg, &debug_msg);
|
||||
|
||||
debug_topic.timestamp = hrt_absolute_time();
|
||||
debug_topic.timestamp_ms = debug_msg.time_boot_ms;
|
||||
debug_topic.ind = debug_msg.ind;
|
||||
debug_topic.value = debug_msg.value;
|
||||
|
||||
if (_debug_value_pub == nullptr) {
|
||||
_debug_value_pub = orb_advertise(ORB_ID(debug_value), &debug_topic);
|
||||
|
||||
} else {
|
||||
orb_publish(ORB_ID(debug_value), _debug_value_pub, &debug_topic);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Receive data from UART.
|
||||
*/
|
||||
|
||||
@@ -67,6 +67,7 @@
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/telemetry_status.h>
|
||||
#include <uORB/topics/debug_key_value.h>
|
||||
#include <uORB/topics/debug_value.h>
|
||||
#include <uORB/topics/airspeed.h>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uORB/topics/vehicle_force_setpoint.h>
|
||||
@@ -152,6 +153,7 @@ private:
|
||||
void handle_message_logging_ack(mavlink_message_t *msg);
|
||||
void handle_message_play_tune(mavlink_message_t *msg);
|
||||
void handle_message_named_value_float(mavlink_message_t *msg);
|
||||
void handle_message_debug(mavlink_message_t *msg);
|
||||
|
||||
void *receive_thread(void *arg);
|
||||
|
||||
@@ -238,6 +240,7 @@ private:
|
||||
orb_advert_t _collision_report_pub;
|
||||
orb_advert_t _control_state_pub;
|
||||
orb_advert_t _debug_key_value_pub;
|
||||
orb_advert_t _debug_value_pub;
|
||||
static const int _gps_inject_data_queue_size = 6;
|
||||
orb_advert_t _gps_inject_data_pub;
|
||||
orb_advert_t _command_ack_pub;
|
||||
|
||||
Reference in New Issue
Block a user