Go to the documentation of this file.
33 #include "sensor_msgs/LaserScan.h"
34 #include "std_msgs/Float64.h"
35 #include "nav_msgs/GetMap.h"
44 #include <boost/thread.hpp>
51 SlamGMapping(
unsigned long int seed,
unsigned long int max_duration_buffer);
56 void startReplay(
const std::string & bag_fname, std::string scan_topic);
59 void laserCallback(
const sensor_msgs::LaserScan::ConstPtr& scan);
61 nav_msgs::GetMap::Response &res);
91 nav_msgs::GetMap::Response
map_;
108 void updateMap(
const sensor_msgs::LaserScan& scan);
110 bool initMapper(
const sensor_msgs::LaserScan& scan);
bool getOdomPose(GMapping::OrientedPoint &gmap_pose, const ros::Time &t)
tf::TransformListener tf_
GMapping::RangeSensor * gsp_laser_
tf::MessageFilter< sensor_msgs::LaserScan > * scan_filter_
double computePoseEntropy()
void updateMap(const sensor_msgs::LaserScan &scan)
unsigned int gsp_laser_beam_count_
bool initMapper(const sensor_msgs::LaserScan &scan)
GMapping::OdometrySensor * gsp_odom_
tf::Stamped< tf::Pose > centered_laser_pose_
tf::TransformBroadcaster * tfB_
ros::Duration map_update_interval_
ros::Publisher entropy_publisher_
void startReplay(const std::string &bag_fname, std::string scan_topic)
tf::Transform map_to_odom_
bool addScan(const sensor_msgs::LaserScan &scan, GMapping::OrientedPoint &gmap_pose)
message_filters::Subscriber< sensor_msgs::LaserScan > * scan_filter_sub_
double resampleThreshold_
boost::mutex map_to_odom_mutex_
void publishLoop(double transform_publish_period)
ros::NodeHandle private_nh_
boost::thread * transform_thread_
double transform_publish_period_
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
nav_msgs::GetMap::Response map_
std::vector< double > laser_angles_
void laserCallback(const sensor_msgs::LaserScan::ConstPtr &scan)
GMapping::GridSlamProcessor * gsp_
gmapping
Author(s): Brian Gerkey
autogenerated on Wed Aug 21 2024 02:12:11