29 #ifndef HECTOR_MAPPING_ROS_H__ 30 #define HECTOR_MAPPING_ROS_H__ 39 #include "sensor_msgs/LaserScan.h" 40 #include <std_msgs/String.h> 43 #include "nav_msgs/GetMap.h" 50 #include <boost/thread.hpp> 63 nav_msgs::GetMap::Response
map_;
74 void scanCallback(
const sensor_msgs::LaserScan& scan);
75 void sysMsgCallback(
const std_msgs::String&
string);
77 bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
81 bool rosLaserScanToDataContainer(
const sensor_msgs::LaserScan& scan,
hectorslam::DataContainer& dataContainer,
float scaleToMap);
84 void setServiceGetMapData(nav_msgs::GetMap::Response& map_,
const hectorslam::GridMap& gridMap);
86 void publishTransformLoop(
double p_transform_pub_period_);
87 void publishMapLoop(
double p_map_pub_period_);
88 void publishTransform();
90 void staticMapCallback(
const nav_msgs::OccupancyGrid& map);
91 void initialPoseCallback(
const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg);
tf::TransformBroadcaster * tfB_
ros::Publisher odometryPublisher_
bool p_pub_map_scanmatch_transform_
tf::MessageFilter< geometry_msgs::PoseWithCovarianceStamped > * initial_pose_filter_
HectorDebugInfoProvider * debugInfoProvider
double p_update_factor_free_
float p_sqr_laser_max_dist_
Eigen::Vector3f lastSlamPose
laser_geometry::LaserProjection projector_
boost::thread * map__publish_thread_
ros::Time lastMapPublishTime
std::vector< MapPublisherContainer > mapPubContainer
bool p_map_with_known_poses_
ros::Publisher mapPublisher_
double p_map_update_distance_threshold_
PoseInfoContainer poseInfoContainer_
int p_map_multi_res_levels_
std::string p_scan_topic_
ros::Subscriber scanSubscriber_
bool p_use_tf_pose_start_estimate_
nav_msgs::GetMap::Response map_
hectorslam::HectorSlamProcessor * slamProcessor
bool p_advertise_map_service_
Eigen::Vector3f initial_pose_
ros::ServiceServer dynamicMapServiceServer_
HectorDrawings * hectorDrawings
ros::Publisher scan_point_cloud_publisher_
std::string p_tf_map_scanmatch_transform_frame_name_
sensor_msgs::PointCloud laser_point_cloud_
ros::Subscriber sysMsgSubscriber_
ros::Publisher posePublisher_
double p_map_update_angle_threshold_
std::string p_odom_frame_
bool p_pub_map_odom_transform_
float p_laser_z_max_value_
std::string p_pose_update_topic_
ros::Publisher mapMetadataPublisher_
bool p_use_tf_scan_transformation_
std::string p_twist_update_topic_
float p_sqr_laser_min_dist_
double p_update_factor_occupied_
hectorslam::DataContainer laserScanContainer
std::string p_sys_msg_topic_
int p_scan_subscriber_queue_size_
ros::Publisher poseUpdatePublisher_
ros::Subscriber mapSubscriber_
std::string p_base_frame_
tf::Transform map_to_odom_
float p_laser_z_min_value_
tf::TransformListener tf_
message_filters::Subscriber< geometry_msgs::PoseWithCovarianceStamped > * initial_pose_sub_
ros::Publisher twistUpdatePublisher_
int lastGetMapUpdateIndex