HectorMappingRos.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef HECTOR_MAPPING_ROS_H__
30 #define HECTOR_MAPPING_ROS_H__
31 
32 #include "ros/ros.h"
33 
34 #include "tf/transform_listener.h"
36 #include "tf/message_filter.h"
38 
39 #include "sensor_msgs/LaserScan.h"
40 #include <std_msgs/String.h>
41 
43 #include "nav_msgs/GetMap.h"
44 
46 
49 
50 #include <boost/thread.hpp>
51 
52 #include "PoseInfoContainer.h"
53 
54 
55 class HectorDrawings;
57 
59 {
60 public:
63  nav_msgs::GetMap::Response map_;
65 };
66 
68 {
69 public:
72 
73 
74  void scanCallback(const sensor_msgs::LaserScan& scan);
75  void sysMsgCallback(const std_msgs::String& string);
76 
77  bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
78 
79  void publishMap(MapPublisherContainer& map_, const hectorslam::GridMap& gridMap, ros::Time timestamp, MapLockerInterface* mapMutex = 0);
80 
81  bool rosLaserScanToDataContainer(const sensor_msgs::LaserScan& scan, hectorslam::DataContainer& dataContainer, float scaleToMap);
82  bool rosPointCloudToDataContainer(const sensor_msgs::PointCloud& pointCloud, const tf::StampedTransform& laserTransform, hectorslam::DataContainer& dataContainer, float scaleToMap);
83 
84  void setServiceGetMapData(nav_msgs::GetMap::Response& map_, const hectorslam::GridMap& gridMap);
85 
86  void publishTransformLoop(double p_transform_pub_period_);
87  void publishMapLoop(double p_map_pub_period_);
88  void publishTransform();
89 
90  void staticMapCallback(const nav_msgs::OccupancyGrid& map);
91  void initialPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg);
92 
93  /*
94  void setStaticMapData(const nav_msgs::OccupancyGrid& map);
95  */
96 protected:
97 
100 
102 
104 
107 
111 
117 
118  std::vector<MapPublisherContainer> mapPubContainer;
119 
122 
124 
126 
127  boost::thread* map__publish_thread_;
128 
131 
133 
134  sensor_msgs::PointCloud laser_point_cloud_;
135 
138  Eigen::Vector3f lastSlamPose;
139 
141  Eigen::Vector3f initial_pose_;
142 
143 
144  //-----------------------------------------------------------
145  // Parameters
146 
147  std::string p_base_frame_;
148  std::string p_map_frame_;
149  std::string p_odom_frame_;
150 
151  //Parameters related to publishing the scanmatcher pose directly via tf
154 
155  std::string p_scan_topic_;
156  std::string p_sys_msg_topic_;
157 
158  std::string p_pose_update_topic_;
160 
167 
172 
178 
180 
185 
186 
191 };
192 
193 #endif
tf::TransformBroadcaster * tfB_
ros::Publisher odometryPublisher_
bool p_pub_map_scanmatch_transform_
tf::MessageFilter< geometry_msgs::PoseWithCovarianceStamped > * initial_pose_filter_
HectorDebugInfoProvider * debugInfoProvider
Eigen::Vector3f lastSlamPose
laser_geometry::LaserProjection projector_
boost::thread * map__publish_thread_
ros::Time lastMapPublishTime
std::vector< MapPublisherContainer > mapPubContainer
ros::Publisher mapPublisher_
double p_map_update_distance_threshold_
PoseInfoContainer poseInfoContainer_
std::string p_scan_topic_
ros::Subscriber scanSubscriber_
bool p_use_tf_pose_start_estimate_
nav_msgs::GetMap::Response map_
hectorslam::HectorSlamProcessor * slamProcessor
Eigen::Vector3f initial_pose_
ros::ServiceServer dynamicMapServiceServer_
ros::NodeHandle node_
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_
std::string p_map_frame_
std::string p_pose_update_topic_
ros::Publisher mapMetadataPublisher_
bool p_use_tf_scan_transformation_
std::string p_twist_update_topic_
double p_update_factor_occupied_
hectorslam::DataContainer laserScanContainer
std::string p_sys_msg_topic_
ros::Publisher poseUpdatePublisher_
ros::Subscriber mapSubscriber_
std::string p_base_frame_
tf::Transform map_to_odom_
tf::TransformListener tf_
message_filters::Subscriber< geometry_msgs::PoseWithCovarianceStamped > * initial_pose_sub_
ros::Publisher twistUpdatePublisher_


hector_mapping
Author(s): Stefan Kohlbrecher
autogenerated on Sun Nov 3 2019 03:18:33