12 #include <nav_msgs/OccupancyGrid.h> 13 #include <nav_msgs/Path.h> 15 #include <mrpt_msgs/GraphSlamAgents.h> 17 #include <mrpt/maps/COccupancyGridMap2D.h> 18 #include <mrpt/math/utils.h> 20 namespace mrpt {
namespace graphslam {
30 mrpt::utils::COutputLogger* logger_in,
31 const mrpt_msgs::GraphSlamAgent& agent_in,
42 const nav_msgs::OccupancyGrid::ConstPtr& nav_gridmap);
47 const nav_msgs::Path::ConstPtr& nav_robot_traj);
57 const mrpt_msgs::GraphSlamAgent&
agent;
59 nav_msgs::OccupancyGrid::ConstPtr
nav_map;
std::string robot_trajectory_topic
void updateRobotTrajectory(const nav_msgs::Path::ConstPtr &nav_robot_traj)
Callback method to be called when new data in the Estimated Trajectory topic is available.
void updateGridMap(const nav_msgs::OccupancyGrid::ConstPtr &nav_gridmap)
Callback method to be called when new data in the map topic is available.
mrpt::utils::COutputLogger * m_logger
size_t getNodeCount()
Return how many nodes have been registered in the fetched robot trajectory.
nav_msgs::Path::ConstPtr nav_robot_trajectory
Trajectory of the correspondign agent - in ROS form.
ros::Subscriber robot_trajectory_sub
const mrpt_msgs::GraphSlamAgent & agent
Pointer to the GraphSlamAgent instance of the neighbor.
Struct holding a COccupancyGridMap2D (as well as subscribers for updating it) for a specific running ...
ros::Subscriber map_sub
Map subscriber instance.
nav_msgs::OccupancyGrid::ConstPtr nav_map
Map generated by the corresponding agent - in ROS form.
std::string map_topic
Map topic to subscribe and fetch the map from.
TNeighborAgentMapProps(mrpt::utils::COutputLogger *logger_in, const mrpt_msgs::GraphSlamAgent &agent_in, ros::NodeHandle *nh_in)