TNeighborAgentMapProps.cpp
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 
00010 #include "mrpt_graphslam_2d/TNeighborAgentMapProps.h"
00011 
00012 using namespace mrpt_msgs;
00013 using namespace mrpt::maps;
00014 using namespace mrpt::graphslam;
00015 using namespace ros;
00016 using namespace mrpt::utils;
00017 using namespace nav_msgs;
00018 using namespace std;
00019 
00020 
00021 TNeighborAgentMapProps::TNeighborAgentMapProps(
00022                 mrpt::utils::COutputLogger* logger_in,
00023                 const mrpt_msgs::GraphSlamAgent& agent_in,
00024                 ros::NodeHandle* nh_in): 
00025         m_logger(logger_in),
00026         nh(nh_in),
00027         agent(agent_in),
00028         queue_size(1),
00029         has_init_class(false),
00030         has_setup_comm(false)
00031 {
00032         ASSERT_(nh);
00033         ASSERT_(m_logger);
00034         m_logger->logFmt(LVL_WARN, "In TNeighborAgentMapProps constructor");
00035 
00036         this->map_topic = "/" + agent.topic_namespace.data + "/" +
00037                 "feedback" + "/" + "gridmap";
00038         this->robot_trajectory_topic = "/" + agent.topic_namespace.data + "/" +
00039                 "feedback" + "/" + "robot_trajectory";
00040 
00041         cout << "Map topic: " << this->map_topic << endl;
00042         cout << "Trajectory topic: " << this->robot_trajectory_topic << endl;
00043 
00044         has_init_class = true;
00045         readROSParameters();
00046 
00047 }
00048 
00049 void TNeighborAgentMapProps::readROSParameters() {
00050         //std::map<std::sttring, std::string> agent_pose;
00051         //bool res = nh->getParam("/" + agent.topic_namespace.data + "/" + "global_pos", agent_pose);
00052 
00053         //if (res) {
00054                 //m_logger->logFmt(LVL_INFO, "%s", getMapAsString(agent_pose).c_str());
00055 
00056                 //global_init_pos = pose_t(
00057                                 //atof(pos_x),
00058                                 //atof(pos_y),
00059                                 //atof(rot_z));
00060                 //m_logger->logFmt(LVL_INFO, "global_init_pos: %s\n", global_init_pos);
00061         //}
00062         //else {
00063                 //cout << "parameter fetch was not successful" << endl;
00064         //}
00065 
00066 }
00067 
00068 void TNeighborAgentMapProps::setupComm() {
00069         ASSERT_(has_init_class);
00070         m_logger->logFmt(LVL_WARN, "In TNeighborAgentMapProps::setupComm");
00071         this->setupSubs();
00072         has_setup_comm = true;
00073 }
00074 
00075 void TNeighborAgentMapProps::setupSubs() {
00076         m_logger->logFmt(LVL_WARN, "In TNeighborAgentMapProps::setupSubs");
00077         this->map_sub  = nh->subscribe<nav_msgs::OccupancyGrid>(
00078                         this->map_topic,
00079                         this->queue_size,
00080                         &TNeighborAgentMapProps::updateGridMap, this);
00081 
00082         this->robot_trajectory_sub  = nh->subscribe<nav_msgs::Path>(
00083                         this->robot_trajectory_topic,
00084                         this->queue_size,
00085                         &TNeighborAgentMapProps::updateRobotTrajectory, this);
00086 } // end of setupSubs
00087 
00088 void TNeighborAgentMapProps::updateGridMap(
00089                 const nav_msgs::OccupancyGrid::ConstPtr& nav_gridmap) {
00090         nav_map = nav_gridmap;
00091 } // end of updateGridMap
00092 
00093 void TNeighborAgentMapProps::updateRobotTrajectory(
00094                 const nav_msgs::Path::ConstPtr& nav_robot_traj) {
00095         nav_robot_trajectory = nav_robot_traj;
00096 }
00097 


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