mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-19 19:04:33 +08:00
Added rangefinder message to MAVLink app
This commit is contained in:
@@ -1942,6 +1942,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
configure_stream("NAMED_VALUE_FLOAT", 1.0f * rate_mult);
|
||||
configure_stream("GLOBAL_POSITION_SETPOINT_INT", 3.0f * rate_mult);
|
||||
configure_stream("ROLL_PITCH_YAW_THRUST_SETPOINT", 3.0f * rate_mult);
|
||||
configure_stream("DISTANCE_SENSOR", 0.5f);
|
||||
break;
|
||||
|
||||
case MAVLINK_MODE_CAMERA:
|
||||
|
||||
@@ -72,6 +72,7 @@
|
||||
#include <uORB/topics/navigation_capabilities.h>
|
||||
#include <drivers/drv_rc_input.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <drivers/drv_range_finder.h>
|
||||
|
||||
#include "mavlink_messages.h"
|
||||
|
||||
@@ -1271,6 +1272,51 @@ protected:
|
||||
}
|
||||
};
|
||||
|
||||
class MavlinkStreamDistanceSensor : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
const char *get_name()
|
||||
{
|
||||
return "DISTANCE_SENSOR";
|
||||
}
|
||||
|
||||
MavlinkStream *new_instance()
|
||||
{
|
||||
return new MavlinkStreamDistanceSensor();
|
||||
}
|
||||
|
||||
private:
|
||||
MavlinkOrbSubscription *range_sub;
|
||||
struct range_finder_report *range;
|
||||
|
||||
protected:
|
||||
void subscribe(Mavlink *mavlink)
|
||||
{
|
||||
range_sub = mavlink->add_orb_subscription(ORB_ID(sensor_range_finder));
|
||||
range = (struct range_finder_report *)range_sub->get_data();
|
||||
}
|
||||
|
||||
void send(const hrt_abstime t)
|
||||
{
|
||||
(void)range_sub->update(t);
|
||||
|
||||
uint8_t type;
|
||||
|
||||
switch (range->type) {
|
||||
case RANGE_FINDER_TYPE_LASER:
|
||||
type = MAV_DISTANCE_SENSOR_LASER;
|
||||
break;
|
||||
}
|
||||
|
||||
uint8_t id = 0;
|
||||
uint8_t orientation = 0;
|
||||
uint8_t covariance = 20;
|
||||
|
||||
mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation,
|
||||
range->minimum_distance*100, range->maximum_distance*100, range->distance*100, covariance);
|
||||
}
|
||||
};
|
||||
|
||||
MavlinkStream *streams_list[] = {
|
||||
new MavlinkStreamHeartbeat(),
|
||||
new MavlinkStreamSysStatus(),
|
||||
@@ -1297,5 +1343,6 @@ MavlinkStream *streams_list[] = {
|
||||
new MavlinkStreamAttitudeControls(),
|
||||
new MavlinkStreamNamedValueFloat(),
|
||||
new MavlinkStreamCameraCapture(),
|
||||
new MavlinkStreamDistanceSensor(),
|
||||
nullptr
|
||||
};
|
||||
|
||||
@@ -46,3 +46,5 @@ SRCS += mavlink_main.cpp \
|
||||
mavlink_commands.cpp
|
||||
|
||||
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
Reference in New Issue
Block a user