18 #include <sensor_msgs/Range.h> 21 namespace extra_plugins {
53 void handle_rangefinder(
const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::RANGEFINDER &rangefinder) {
54 auto rangefinder_msg = boost::make_shared<sensor_msgs::Range>();
56 rangefinder_msg->header.frame_id =
"/rangefinder";
57 rangefinder_msg->radiation_type = sensor_msgs::Range::INFRARED;
58 rangefinder_msg->field_of_view = 0;
59 rangefinder_msg->min_range = 0;
60 rangefinder_msg->max_range = 1000;
61 rangefinder_msg->range = rangefinder.distance;
63 rangefinder_pub.
publish(rangefinder_msg);
void handle_rangefinder(const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::RANGEFINDER &rangefinder)
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher rangefinder_pub
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
ros::NodeHandle rangefinder_nh
void initialize(UAS &uas_)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Subscriptions get_subscriptions()
std::vector< HandlerInfo > Subscriptions
void initialize(UAS &uas_)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)