21 #ifndef _PLUGINS_AMCL_ROS_THREAD_H_
22 #define _PLUGINS_AMCL_ROS_THREAD_H_
25 # error "ROS integration requires ROS support of system"
28 #include "amcl_thread.h"
32 #include <aspect/blackboard.h>
33 #include <aspect/configurable.h>
34 #include <aspect/logging.h>
35 #include <core/threading/thread.h>
36 #include <geometry_msgs/PoseWithCovarianceStamped.h>
37 #include <interfaces/LocalizationInterface.h>
38 #include <plugins/ros/aspect/ros.h>
39 #include <ros/publisher.h>
40 #include <ros/subscriber.h>
62 void publish_pose_array(
const std::string &global_frame_id,
const pf_sample_set_t *set);
65 const double last_covariance[36]);
66 void publish_map(
const std::string &global_frame_id,
const map_t *map);
77 void initial_pose_received(
const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg);
80 std::string cfg_pose_ifname_;
84 ros::Publisher pose_pub_;
85 ros::Publisher particlecloud_pub_;
86 ros::Subscriber initial_pose_sub_;
87 ros::Publisher map_pub_;