33 #include <geometry_msgs/PoseWithCovarianceStamped.h> 34 #include <nav_msgs/Odometry.h> 36 #include "sensor_msgs/PointCloud2.h" 47 : debugInfoProvider(0)
49 , lastGetMapUpdateIndex(-100)
51 , map__publish_thread_(0)
52 , initial_pose_set_(false)
56 std::string mapTopic_ =
"map";
97 private_nh_.
param(
"laser_min_dist", tmp, 0.4);
100 private_nh_.
param(
"laser_max_dist", tmp, 30.0);
103 private_nh_.
param(
"laser_z_min_value", tmp, -1.0);
106 private_nh_.
param(
"laser_z_max_value", tmp, 1.0);
111 ROS_INFO(
"HectorSM publishing debug drawings");
117 ROS_INFO(
"HectorSM publishing debug info");
132 int mapLevels = slamProcessor->getMapLevels();
135 for (
int i = 0; i < mapLevels; ++i)
140 std::string mapTopicStr(mapTopic_);
144 mapTopicStr.append(
"_" + boost::lexical_cast<std::string>(i));
147 std::string mapMetaTopicStr(mapTopicStr);
148 mapMetaTopicStr.append(
"_metadata");
261 Eigen::Vector3f startEstimate(Eigen::Vector3f::Zero());
301 ROS_INFO(
"lookupTransform %s to %s timed out. Could not transform laser scan into base_frame.",
p_base_frame_.c_str(), scan.header.frame_id.c_str());
309 ROS_INFO(
"HectorSLAM Iter took: %f milliseconds", duration.
toSec()*1000.0f );
325 nav_msgs::Odometry tmp;
344 ROS_ERROR(
"Transform failed during publishing of map_odom transform: %s",e.what());
358 ROS_INFO(
"HectorSM sysMsgCallback, msg contents: %s",
string.data.c_str());
360 if (
string.data ==
"reset")
368 nav_msgs::GetMap::Response &res)
370 ROS_INFO(
"HectorSM Map service called");
377 nav_msgs::GetMap::Response& map_ (mapPublisher.
map_);
386 int size = sizeX * sizeY;
388 std::vector<int8_t>& data = map_.map.data;
391 memset(&data[0], -1,
sizeof(int8_t) * size);
398 for(
int i=0; i < size; ++i)
418 map_.map.header.stamp = timestamp;
425 size_t size = scan.ranges.size();
427 float angle = scan.angle_min;
429 dataContainer.
clear();
431 dataContainer.
setOrigo(Eigen::Vector2f::Zero());
433 float maxRangeForContainer = scan.range_max - 0.1f;
435 for (
size_t i = 0; i < size; ++i)
437 float dist = scan.ranges[i];
439 if ( (dist > scan.range_min) && (dist < maxRangeForContainer))
442 dataContainer.
add(Eigen::Vector2f(
cos(angle) * dist,
sin(angle) * dist));
445 angle += scan.angle_increment;
453 size_t size = pointCloud.points.size();
456 dataContainer.
clear();
459 dataContainer.
setOrigo(Eigen::Vector2f(laserPos.x(), laserPos.y())*scaleToMap);
461 for (
size_t i = 0; i < size; ++i)
464 const geometry_msgs::Point32& currPoint(pointCloud.points[i]);
466 float dist_sqr = currPoint.x*currPoint.x + currPoint.y* currPoint.y;
470 if ( (currPoint.x < 0.0f) && (dist_sqr < 0.50f)){
476 float pointPosLaserFrameZ = pointPosBaseFrame.
z() - laserPos.z();
480 dataContainer.
add(Eigen::Vector2f(pointPosBaseFrame.
x(),pointPosBaseFrame.
y())*scaleToMap);
490 Eigen::Vector2f mapOrigin (gridMap.
getWorldCoords(Eigen::Vector2f::Zero()));
493 map_.map.info.origin.position.x = mapOrigin.x();
494 map_.map.info.origin.position.y = mapOrigin.y();
495 map_.map.info.origin.orientation.w = 1.0;
499 map_.map.info.width = gridMap.
getSizeX();
500 map_.map.info.height = gridMap.
getSizeY();
503 map_.map.data.resize(map_.map.info.width * map_.map.info.height);
bool rosLaserScanToDataContainer(const sensor_msgs::LaserScan &scan, hectorslam::DataContainer &dataContainer, float scaleToMap)
void projectLaser(const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default)
tf::TransformBroadcaster * tfB_
ros::Publisher odometryPublisher_
bool p_pub_map_scanmatch_transform_
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
tf::MessageFilter< geometry_msgs::PoseWithCovarianceStamped > * initial_pose_filter_
HectorDebugInfoProvider * debugInfoProvider
double p_update_factor_free_
void publishMap(MapPublisherContainer &map_, const hectorslam::GridMap &gridMap, ros::Time timestamp, MapLockerInterface *mapMutex=0)
float p_sqr_laser_max_dist_
void publish(const boost::shared_ptr< M > &message) const
laser_geometry::LaserProjection projector_
void staticMapCallback(const nav_msgs::OccupancyGrid &map)
const geometry_msgs::PoseStamped & getPoseStamped()
boost::thread * map__publish_thread_
ros::Time lastMapPublishTime
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
std::vector< MapPublisherContainer > mapPubContainer
static double getYaw(const Quaternion &bt_q)
const geometry_msgs::PoseWithCovarianceStamped & getPoseWithCovarianceStamped()
bool p_map_with_known_poses_
void update(const Eigen::Vector3f &slamPose, const Eigen::Matrix3f &slamCov, const ros::Time &stamp, const std::string &frame_id)
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
void setOrigo(const DataPointType &origoIn)
ros::Publisher mapPublisher_
double p_map_update_distance_threshold_
PoseInfoContainer poseInfoContainer_
int p_map_multi_res_levels_
TFSIMD_FORCE_INLINE const tfScalar & getY() const
std::string p_scan_topic_
ros::Subscriber scanSubscriber_
const tf::Transform & getTfTransform()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool p_use_tf_pose_start_estimate_
nav_msgs::GetMap::Response map_
const Eigen::Vector3f & getLastScanMatchPose() const
MapLockerInterface * getMapMutex(int i)
hectorslam::HectorSlamProcessor * slamProcessor
bool p_advertise_map_service_
Eigen::Vector3f initial_pose_
ros::ServiceServer dynamicMapServiceServer_
const Eigen::Matrix3f & getLastScanMatchCovariance() const
void sysMsgCallback(const std_msgs::String &string)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
HectorDrawings * hectorDrawings
TFSIMD_FORCE_INLINE const tfScalar & x() const
ros::Publisher scan_point_cloud_publisher_
std::string p_tf_map_scanmatch_transform_frame_name_
sensor_msgs::PointCloud laser_point_cloud_
ros::Subscriber sysMsgSubscriber_
bool isOccupied(int xMap, int yMap) const
ros::Publisher posePublisher_
TFSIMD_FORCE_INLINE const tfScalar & z() const
float getScaleToMap() const
bool rosPointCloudToDataContainer(const sensor_msgs::PointCloud &pointCloud, const tf::StampedTransform &laserTransform, hectorslam::DataContainer &dataContainer, float scaleToMap)
int getUpdateIndex() const
void scanCallback(const sensor_msgs::LaserScan &scan)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
double p_map_update_angle_threshold_
std::string p_odom_frame_
TFSIMD_FORCE_INLINE const tfScalar & y() const
bool p_pub_map_odom_transform_
float p_laser_z_max_value_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string p_pose_update_topic_
ros::Publisher mapMetadataPublisher_
bool p_use_tf_scan_transformation_
Eigen::Vector2f getWorldCoords(const Eigen::Vector2f &mapCoords) const
float getCellLength() const
float p_sqr_laser_min_dist_
double p_update_factor_occupied_
uint32_t getNumSubscribers() const
void publishMapLoop(double p_map_pub_period_)
hectorslam::DataContainer laserScanContainer
std::string p_sys_msg_topic_
int p_scan_subscriber_queue_size_
ros::Publisher poseUpdatePublisher_
const GridMap & getGridMap(int mapLevel=0) const
TFSIMD_FORCE_INLINE const tfScalar & getX() const
void setTime(const ros::Time &time)
bool isFree(int xMap, int yMap) const
void initialPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
virtual void unlockMap()=0
void update(const DataContainer &dataContainer, const Eigen::Vector3f &poseHintWorld, bool map_without_matching=false)
void setServiceGetMapData(nav_msgs::GetMap::Response &map_, const hectorslam::GridMap &gridMap)
void add(const DataPointType &dataPoint)
std::string p_base_frame_
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
tf::Transform map_to_odom_
float p_laser_z_min_value_
tf::TransformListener tf_
message_filters::Subscriber< geometry_msgs::PoseWithCovarianceStamped > * initial_pose_sub_
Connection registerCallback(const C &callback)
int lastGetMapUpdateIndex