TNeighborAgentMapProps.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 #pragma once
10 
11 #include <ros/ros.h>
12 #include <nav_msgs/OccupancyGrid.h>
13 #include <nav_msgs/Path.h>
14 #include <mrpt_bridge/map.h>
15 #include <mrpt_msgs/GraphSlamAgents.h>
16 #include <mrpt/utils/COutputLogger.h>
17 #include <mrpt/maps/COccupancyGridMap2D.h>
18 #include <mrpt/math/utils.h>
19 
20 namespace mrpt { namespace graphslam {
21 
28 {
30  mrpt::utils::COutputLogger* logger_in,
31  const mrpt_msgs::GraphSlamAgent& agent_in,
32  ros::NodeHandle* nh_in);
33 
34  void readROSParameters();
35  void setupComm();
36  void setupSubs();
37  void setupPubs();
41  void updateGridMap(
42  const nav_msgs::OccupancyGrid::ConstPtr& nav_gridmap);
47  const nav_msgs::Path::ConstPtr& nav_robot_traj);
48 
52  size_t getNodeCount() { return nav_robot_trajectory->poses.size(); }
53 
54  mrpt::utils::COutputLogger* m_logger;
57  const mrpt_msgs::GraphSlamAgent& agent;
59  nav_msgs::OccupancyGrid::ConstPtr nav_map;
61  nav_msgs::Path::ConstPtr nav_robot_trajectory;
71  std::string map_topic;
74  size_t queue_size;
77 
78 
79 }; // end of TNeighborAgentMapProps
80 
81 } } // end of namespaces
82 
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.
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.
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)


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Jun 6 2019 19:37:48