TNeighborAgentMapProps.h
Go to the documentation of this file.
00001 /* +---------------------------------------------------------------------------+
00002    |                     Mobile Robot Programming Toolkit (MRPT)               |
00003    |                          http://www.mrpt.org/                             |
00004    |                                                                           |
00005    | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file        |
00006    | See: http://www.mrpt.org/Authors - All rights reserved.                   |
00007    | Released under BSD License. See details in http://www.mrpt.org/License    |
00008    +---------------------------------------------------------------------------+ */
00009 #ifndef TNEIGHBORAGENTMAPPROPS_H
00010 #define TNEIGHBORAGENTMAPPROPS_H
00011 
00012 #include <ros/ros.h>
00013 #include <nav_msgs/OccupancyGrid.h>
00014 #include <nav_msgs/Path.h>
00015 #include <mrpt_bridge/map.h>
00016 #include <mrpt_msgs/GraphSlamAgents.h>
00017 #include <mrpt/utils/COutputLogger.h>
00018 #include <mrpt/maps/COccupancyGridMap2D.h>
00019 #include <mrpt/math/utils.h>
00020 
00021 namespace mrpt { namespace graphslam {
00022 
00028 struct TNeighborAgentMapProps
00029 {
00030         TNeighborAgentMapProps(
00031                         mrpt::utils::COutputLogger* logger_in,
00032                         const mrpt_msgs::GraphSlamAgent& agent_in,
00033                         ros::NodeHandle* nh_in);
00034 
00035         void readROSParameters();
00036         void setupComm();
00037         void setupSubs();
00038         void setupPubs();
00042         void updateGridMap(
00043                         const nav_msgs::OccupancyGrid::ConstPtr& nav_gridmap);
00047         void updateRobotTrajectory(
00048                         const nav_msgs::Path::ConstPtr& nav_robot_traj);
00049 
00053         size_t getNodeCount() { return nav_robot_trajectory->poses.size(); }
00054 
00055         ros::NodeHandle* nh;
00057         const mrpt_msgs::GraphSlamAgent& agent;
00059         nav_msgs::OccupancyGrid::ConstPtr nav_map;
00061         nav_msgs::Path::ConstPtr nav_robot_trajectory;
00065         ros::Subscriber map_sub;
00066         ros::Subscriber robot_trajectory_sub;
00071         std::string map_topic;
00072         std::string robot_trajectory_topic;
00074         size_t queue_size;
00075         bool has_init_class;
00076         bool has_setup_comm;
00077         mrpt::utils::COutputLogger* m_logger;
00078 
00079 
00080 }; // end of TNeighborAgentMapProps
00081 
00082 } } // end of namespaces
00083 
00084 #endif /* end of include guard: TNEIGHBORAGENTMAPPROPS_H */


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Sun Sep 17 2017 03:02:04