Go to the documentation of this file.
13 using namespace mrpt::system;
14 using namespace mrpt_msgs;
15 using namespace mrpt::maps;
18 using namespace nav_msgs;
21 TNeighborAgentMapProps::TNeighborAgentMapProps(
22 mrpt::system::COutputLogger* logger_in,
24 : m_logger(logger_in),
28 has_init_class(false),
33 m_logger->logFmt(LVL_WARN,
"In TNeighborAgentMapProps constructor");
36 "/" +
agent.topic_namespace.data +
"/" +
"feedback" +
"/" +
"gridmap";
38 "feedback" +
"/" +
"robot_trajectory";
40 cout <<
"Map topic: " << this->
map_topic << endl;
70 m_logger->logFmt(LVL_WARN,
"In TNeighborAgentMapProps::setupComm");
77 m_logger->logFmt(LVL_WARN,
"In TNeighborAgentMapProps::setupSubs");
88 const nav_msgs::OccupancyGrid::ConstPtr& nav_gridmap)
94 const nav_msgs::Path::ConstPtr& nav_robot_traj)
ros::Subscriber map_sub
Map subscriber instance.
mrpt::system::COutputLogger * m_logger
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.
std::string robot_trajectory_topic
const mrpt_msgs::GraphSlamAgent & agent
Pointer to the GraphSlamAgent instance of the neighbor.
ros::Subscriber robot_trajectory_sub
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
std::string map_topic
Map topic to subscribe and fetch the map from.
nav_msgs::Path::ConstPtr nav_robot_trajectory
Trajectory of the correspondign agent - in ROS form.
void updateGridMap(const nav_msgs::OccupancyGrid::ConstPtr &nav_gridmap)
Callback method to be called when new data in the map topic is available.
nav_msgs::OccupancyGrid::ConstPtr nav_map
Map generated by the corresponding agent - in ROS form.