20 #include "sensor_msgs/LaserScan.h" 21 #include "std_msgs/Float64.h" 22 #include "nav_msgs/GetMap.h" 31 #include <boost/thread.hpp> 38 SlamGMapping(
unsigned long int seed,
unsigned long int max_duration_buffer);
43 void startReplay(
const std::string & bag_fname, std::string scan_topic);
46 void laserCallback(
const sensor_msgs::LaserScan::ConstPtr& scan);
48 nav_msgs::GetMap::Response &res);
78 nav_msgs::GetMap::Response
map_;
95 void updateMap(
const sensor_msgs::LaserScan& scan);
97 bool initMapper(
const sensor_msgs::LaserScan& scan);
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
void laserCallback(const sensor_msgs::LaserScan::ConstPtr &scan)
message_filters::Subscriber< sensor_msgs::LaserScan > * scan_filter_sub_
bool initMapper(const sensor_msgs::LaserScan &scan)
void updateMap(const sensor_msgs::LaserScan &scan)
tf::TransformListener tf_
double computePoseEntropy()
void publishLoop(double transform_publish_period)
bool getOdomPose(GMapping::OrientedPoint &gmap_pose, const ros::Time &t)
tf::Stamped< tf::Pose > centered_laser_pose_
unsigned int gsp_laser_beam_count_
tf::TransformBroadcaster * tfB_
void startReplay(const std::string &bag_fname, std::string scan_topic)
tf::Transform map_to_odom_
nav_msgs::GetMap::Response map_
boost::mutex map_to_odom_mutex_
boost::thread * transform_thread_
ros::Publisher entropy_publisher_
ros::Duration map_update_interval_
double transform_publish_period_
ros::NodeHandle private_nh_
GMapping::GridSlamProcessor * gsp_
double resampleThreshold_
std::vector< double > laser_angles_
tf::MessageFilter< sensor_msgs::LaserScan > * scan_filter_
GMapping::OdometrySensor * gsp_odom_
GMapping::RangeSensor * gsp_laser_
bool addScan(const sensor_msgs::LaserScan &scan, GMapping::OrientedPoint &gmap_pose)