aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_messages.cpp
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-04-13 23:30:09 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-04-13 23:30:09 +0200
commitf84669039579aeef80e232c3c9a444d20bcbdf39 (patch)
tree59aa9cc1d55aa2aafcf07b08c10c27ff4f9dc399 /src/modules/mavlink/mavlink_messages.cpp
parent80cd2e6c9b03eb078aafe2814ff1c9d2753ac073 (diff)
downloadpx4-firmware-f84669039579aeef80e232c3c9a444d20bcbdf39.tar.gz
px4-firmware-f84669039579aeef80e232c3c9a444d20bcbdf39.tar.bz2
px4-firmware-f84669039579aeef80e232c3c9a444d20bcbdf39.zip
Added rangefinder message to MAVLink app
Diffstat (limited to 'src/modules/mavlink/mavlink_messages.cpp')
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp47
1 files changed, 47 insertions, 0 deletions
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 47603b390..e608bf787 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -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
};