Struct holding a COccupancyGridMap2D (as well as subscribers for updating it) for a specific running GraphSlamAgent instance. More...
#include <TNeighborAgentMapProps.h>
Public Member Functions | |
size_t | getNodeCount () |
Return how many nodes have been registered in the fetched robot trajectory. | |
void | readROSParameters () |
void | setupComm () |
void | setupPubs () |
void | setupSubs () |
TNeighborAgentMapProps (mrpt::utils::COutputLogger *logger_in, const mrpt_msgs::GraphSlamAgent &agent_in, ros::NodeHandle *nh_in) | |
void | updateGridMap (const nav_msgs::OccupancyGrid::ConstPtr &nav_gridmap) |
Callback method to be called when new data in the map topic is available. | |
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. | |
Public Attributes | |
const mrpt_msgs::GraphSlamAgent & | agent |
Pointer to the GraphSlamAgent instance of the neighbor. | |
bool | has_init_class |
bool | has_setup_comm |
mrpt::utils::COutputLogger * | m_logger |
nav_msgs::OccupancyGrid::ConstPtr | nav_map |
Map generated by the corresponding agent - in ROS form. | |
nav_msgs::Path::ConstPtr | nav_robot_trajectory |
Trajectory of the correspondign agent - in ROS form. | |
ros::NodeHandle * | nh |
size_t | queue_size |
Subscriber instances | |
ros::Subscriber | map_sub |
Map subscriber instance. | |
ros::Subscriber | robot_trajectory_sub |
Topic names | |
std::string | map_topic |
Map topic to subscribe and fetch the map from. | |
std::string | robot_trajectory_topic |
Struct holding a COccupancyGridMap2D (as well as subscribers for updating it) for a specific running GraphSlamAgent instance.
Definition at line 27 of file TNeighborAgentMapProps.h.
TNeighborAgentMapProps::TNeighborAgentMapProps | ( | mrpt::utils::COutputLogger * | logger_in, |
const mrpt_msgs::GraphSlamAgent & | agent_in, | ||
ros::NodeHandle * | nh_in | ||
) |
Definition at line 27 of file TNeighborAgentMapProps.cpp.
size_t mrpt::graphslam::TNeighborAgentMapProps::getNodeCount | ( | ) | [inline] |
Return how many nodes have been registered in the fetched robot trajectory.
Definition at line 52 of file TNeighborAgentMapProps.h.
Definition at line 55 of file TNeighborAgentMapProps.cpp.
void TNeighborAgentMapProps::setupComm | ( | ) |
Definition at line 74 of file TNeighborAgentMapProps.cpp.
void TNeighborAgentMapProps::setupSubs | ( | ) |
Definition at line 81 of file TNeighborAgentMapProps.cpp.
void TNeighborAgentMapProps::updateGridMap | ( | const nav_msgs::OccupancyGrid::ConstPtr & | nav_gridmap | ) |
Callback method to be called when new data in the map topic is available.
Definition at line 94 of file TNeighborAgentMapProps.cpp.
void TNeighborAgentMapProps::updateRobotTrajectory | ( | const nav_msgs::Path::ConstPtr & | nav_robot_traj | ) |
Callback method to be called when new data in the Estimated Trajectory topic is available.
Definition at line 99 of file TNeighborAgentMapProps.cpp.
const mrpt_msgs::GraphSlamAgent& mrpt::graphslam::TNeighborAgentMapProps::agent |
Pointer to the GraphSlamAgent instance of the neighbor.
Definition at line 57 of file TNeighborAgentMapProps.h.
Definition at line 75 of file TNeighborAgentMapProps.h.
Definition at line 76 of file TNeighborAgentMapProps.h.
mrpt::utils::COutputLogger* mrpt::graphslam::TNeighborAgentMapProps::m_logger |
Definition at line 54 of file TNeighborAgentMapProps.h.
Map subscriber instance.
Definition at line 65 of file TNeighborAgentMapProps.h.
Map topic to subscribe and fetch the map from.
Definition at line 71 of file TNeighborAgentMapProps.h.
nav_msgs::OccupancyGrid::ConstPtr mrpt::graphslam::TNeighborAgentMapProps::nav_map |
Map generated by the corresponding agent - in ROS form.
Definition at line 59 of file TNeighborAgentMapProps.h.
nav_msgs::Path::ConstPtr mrpt::graphslam::TNeighborAgentMapProps::nav_robot_trajectory |
Trajectory of the correspondign agent - in ROS form.
Definition at line 61 of file TNeighborAgentMapProps.h.
Definition at line 55 of file TNeighborAgentMapProps.h.
Definition at line 74 of file TNeighborAgentMapProps.h.
Definition at line 66 of file TNeighborAgentMapProps.h.
Definition at line 72 of file TNeighborAgentMapProps.h.