Skip to content

Commit

Permalink
mavlink_receiver: decode obstacle_distance message
Browse files Browse the repository at this point in the history
  • Loading branch information
mrivi authored and LorenzMeier committed Feb 16, 2018
1 parent 883fb8c commit f932217
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 0 deletions.
27 changes: 27 additions & 0 deletions src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_telemetry_status_pub(nullptr),
_rc_pub(nullptr),
_manual_pub(nullptr),
_obstacle_distance_pub(nullptr),
_land_detector_pub(nullptr),
_time_offset_pub(nullptr),
_follow_target_pub(nullptr),
Expand Down Expand Up @@ -321,6 +322,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_play_tune(msg);
break;

case MAVLINK_MSG_ID_OBSTACLE_DISTANCE:
handle_message_obstacle_distance(msg);
break;

case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
handle_message_named_value_float(msg);
break;
Expand Down Expand Up @@ -1480,6 +1485,28 @@ MavlinkReceiver::handle_message_play_tune(mavlink_message_t *msg)
}
}

void
MavlinkReceiver::handle_message_obstacle_distance(mavlink_message_t *msg)
{
mavlink_obstacle_distance_t mavlink_obstacle_distance;
mavlink_msg_obstacle_distance_decode(msg, &mavlink_obstacle_distance);

obstacle_distance_s obstacle_distance = {};
obstacle_distance.timestamp = hrt_absolute_time();
obstacle_distance.sensor_type = mavlink_obstacle_distance.sensor_type;
memcpy(obstacle_distance.distances, mavlink_obstacle_distance.distances, sizeof(obstacle_distance.distances));
obstacle_distance.increment = mavlink_obstacle_distance.increment;
obstacle_distance.min_distance = mavlink_obstacle_distance.min_distance;
obstacle_distance.max_distance = mavlink_obstacle_distance.max_distance;

if (_obstacle_distance_pub == nullptr) {
_obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &obstacle_distance);

} else {
orb_publish(ORB_ID(obstacle_distance), _obstacle_distance_pub, &obstacle_distance);
}
}

switch_pos_t
MavlinkReceiver::decode_switch_pos(uint16_t buttons, unsigned sw)
{
Expand Down
3 changes: 3 additions & 0 deletions src/modules/mavlink/mavlink_receiver.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@
#include <uORB/topics/transponder_report.h>
#include <uORB/topics/gps_inject_data.h>
#include <uORB/topics/collision_report.h>
#include <uORB/topics/obstacle_distance.h>

#include "mavlink_mission.h"
#include "mavlink_parameters.h"
Expand Down Expand Up @@ -155,6 +156,7 @@ class MavlinkReceiver
void handle_message_serial_control(mavlink_message_t *msg);
void handle_message_logging_ack(mavlink_message_t *msg);
void handle_message_play_tune(mavlink_message_t *msg);
void handle_message_obstacle_distance(mavlink_message_t *msg);
void handle_message_named_value_float(mavlink_message_t *msg);
void handle_message_debug(mavlink_message_t *msg);
void handle_message_debug_vect(mavlink_message_t *msg);
Expand Down Expand Up @@ -236,6 +238,7 @@ class MavlinkReceiver
orb_advert_t _telemetry_status_pub;
orb_advert_t _rc_pub;
orb_advert_t _manual_pub;
orb_advert_t _obstacle_distance_pub;
orb_advert_t _land_detector_pub;
orb_advert_t _time_offset_pub;
orb_advert_t _follow_target_pub;
Expand Down

1 comment on commit f932217

@ecmnet
Copy link
Contributor

@ecmnet ecmnet commented on f932217 Feb 17, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Two questions from my side:
Is it planned to integrate a local planner into the Firmware? (as the message definition points a bit to a VFH-based local planner)
The message definition currently supports 2D as far as I see. Is it planned to extend this to 3D?

Please sign in to comment.