Public Member Functions | Public Attributes
mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps Struct Reference

Struct responsible for holding properties (nodeIDs, node positions, LaserScans) that have been registered by a nearby GraphSlamAgent. More...

#include <CGraphSlamEngine_MR.h>

List of all members.

Public Member Functions

void computeGridMap () const
 Using the fetched LaserScans and nodeID positions, compute the occupancy gridmap of the given neighbor.
void fillOptPaths (const std::set< TNodeID > &nodeIDs, paths_t *opt_paths) const
 Fill the optimal paths for each combination of the given nodeIDs.
std::string getAgentNs () const
void getCachedNodes (std::vector< TNodeID > *nodeIDs=NULL, std::map< TNodeID, node_props_t > *nodes_params=NULL, bool only_unused=true) const
 Return cached list of nodeIDs (with their corresponding poses, LaserScans)
const
mrpt::maps::COccupancyGridMap2D::Ptr & 
getGridMap () const
void getGridMap (mrpt::maps::COccupancyGridMap2D::Ptr &map) const
 Fill the given occupancy gridmap object with the current neighbor's grdmap.
const sensor_msgs::LaserScangetLaserScanByNodeID (const TNodeID nodeID) const
bool hasNewData () const
 Return True if there are new data (node positions and corresponding LaserScans available)
bool hasNewNodesBatch (int new_batch_size)
 Decide whether there are enough new nodes + scans that have not been integrated in the graph yet.
bool operator< (const TNeighborAgentProps &other) const
bool operator== (const TNeighborAgentProps &other) const
void resetFlags () const
void setTColor (const TColor &color_in)
 Set the color related to the current neighbor agent.
void setupComm ()
 Wrapper for calling setupSubs, setupSrvs.
void setupSrvs ()
 Setup necessary services for neighbor.
void setupSubs ()
 Setup the necessary subscribers for fetching nodes, laserScans for the current neighbor.
 TNeighborAgentProps (CGraphSlamEngine_MR< GRAPH_T > &engine_in, const mrpt_msgs::GraphSlamAgent &agent_in)
 Constructor.
 ~TNeighborAgentProps ()
 Destructor.
Subscriber callback methods

Methods to be called when data is received on the subscribed topics

void fetchUpdatedNodesList (const mrpt_msgs::NodeIDWithPose_vec::ConstPtr &nodes)
 Update nodeIDs + corresponding estimated poses.
void fetchLastRegdIDScan (const mrpt_msgs::NodeIDWithLaserScan::ConstPtr &last_regd_id_scan)
 Fill the LaserScan of the last registered nodeID.

Public Attributes

const mrpt_msgs::GraphSlamAgent agent
TColor color
 Unique color of current TNeighborAgentProps instance.
CGraphSlamEngine_MR< GRAPH_T > & engine
mrpt::maps::COccupancyGridMap2D::Ptr gridmap_cached
 Pointer to the gridmap object of the neighbor.
bool has_new_nodes
bool has_new_scans
bool has_setup_comm
std::pair< TNodeID,
mrpt::poses::CPose2D > 
last_integrated_pair_neighbor_frame
 Last nodeID/CPose2D of neighbor that was integrated - Pose is taken with regards to neighbor's frame of reference.
int m_queue_size
ros::NodeHandlenh
 NodeHandle passed by the calling CGraphSlamEngine_MR class.
mrpt::poses::CPose2D tf_self_to_neighbor_first_integrated_pose
 CPose2D connecting own graph origin to neighbor first received and integrated node. If this pose is 0 then it is not yet computed.
Neighbor cached properties
std::set< TNodeID > nodeIDs_set
 NodeIDs that I have received from this graphSLAM agent.
GRAPH_T::global_poses_t poses
 Poses that I have received from this graphSLAM agent.
std::vector
< mrpt_msgs::NodeIDWithLaserScan > 
ros_scans
 ROS LaserScans that I have received from this graphSLAM agent.
std::map< TNodeID, bool > nodeID_to_is_integrated
 Have I already integrated this node in my graph?
Subscriber/Services Instances
ros::Subscriber last_regd_nodes_sub
ros::Subscriber last_regd_id_scan_sub
ros::ServiceClient cm_graph_srvclient
Full topic names / service names

Names of the full topic paths that the neighbor publishes nodes, LaserScans at.

std::string last_regd_nodes_topic
std::string last_regd_id_scan_topic
std::string cm_graph_service

Detailed Description

template<class GRAPH_T>
struct mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps

Struct responsible for holding properties (nodeIDs, node positions, LaserScans) that have been registered by a nearby GraphSlamAgent.

Definition at line 115 of file CGraphSlamEngine_MR.h.


Constructor & Destructor Documentation

template<class GRAPH_T >
mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::TNeighborAgentProps ( CGraphSlamEngine_MR< GRAPH_T > &  engine_in,
const mrpt_msgs::GraphSlamAgent &  agent_in 
)

Constructor.

Definition at line 1044 of file CGraphSlamEngine_MR_impl.h.

Destructor.

Definition at line 1083 of file CGraphSlamEngine_MR_impl.h.


Member Function Documentation

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::computeGridMap ( ) const

Using the fetched LaserScans and nodeID positions, compute the occupancy gridmap of the given neighbor.

Definition at line 1384 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::fetchLastRegdIDScan ( const mrpt_msgs::NodeIDWithLaserScan::ConstPtr &  last_regd_id_scan)

Fill the LaserScan of the last registered nodeID.

Definition at line 1193 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::fetchUpdatedNodesList ( const mrpt_msgs::NodeIDWithPose_vec::ConstPtr &  nodes)

Update nodeIDs + corresponding estimated poses.

Definition at line 1126 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::fillOptPaths ( const std::set< TNodeID > &  nodeIDs,
paths_t opt_paths 
) const

Fill the optimal paths for each combination of the given nodeIDs.

Definition at line 1335 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T>
std::string mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::getAgentNs ( ) const [inline]

Definition at line 186 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::getCachedNodes ( std::vector< TNodeID > *  nodeIDs = NULL,
std::map< TNodeID, node_props_t > *  nodes_params = NULL,
bool  only_unused = true 
) const

Return cached list of nodeIDs (with their corresponding poses, LaserScans)

Parameters:
[in]only_unusedInclude only the nodes that have not already been used in the current CGraphSlamEngine's graph
[out]nodeIDsPointer to vector of nodeIDs that are actually returned. This argument is redundant but may be convinient in case that just the nodeIDs are required
[out]node_paramsPointer to the map of nodeIDs Corresponding properties that is to be filled by the method
Note:
Method also calls resetFlags
See also:
resetFlags

Definition at line 1211 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T >
const mrpt::maps::COccupancyGridMap2D::Ptr & mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::getGridMap ( ) const

Definition at line 1414 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::getGridMap ( mrpt::maps::COccupancyGridMap2D::Ptr &  map) const

Fill the given occupancy gridmap object with the current neighbor's grdmap.

Definition at line 1426 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T >
const sensor_msgs::LaserScan * mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::getLaserScanByNodeID ( const TNodeID  nodeID) const

Utility method for fetching the ROS LaserScan that corresponds to a nodeID.

Definition at line 1312 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::hasNewData ( ) const

Return True if there are new data (node positions and corresponding LaserScans available)

Caller is responsible of setting the underlying has_new_* variables to false using the resetFlags method upon successful integration of (some of) the nodes

Definition at line 1440 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::hasNewNodesBatch ( int  new_batch_size)

Decide whether there are enough new nodes + scans that have not been integrated in the graph yet.

Method takes in account only the nodeIDs that have a valid LaserScan

Returns:
True if there are more than new_batch_size valid nodes + scans available for integration, false otherwise

Definition at line 1292 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T>
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::operator< ( const TNeighborAgentProps other) const [inline]

Definition at line 192 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::operator== ( const TNeighborAgentProps other) const [inline]

Definition at line 188 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::resetFlags ( ) const

Definition at line 1284 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T>
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::setTColor ( const TColor &  color_in) [inline]

Set the color related to the current neighbor agent.

Handy in visualization operations

Definition at line 223 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::setupComm ( )

Wrapper for calling setupSubs, setupSrvs.

Definition at line 1086 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::setupSrvs ( )

Setup necessary services for neighbor.

Definition at line 1102 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::setupSubs ( )

Setup the necessary subscribers for fetching nodes, laserScans for the current neighbor.

Definition at line 1110 of file CGraphSlamEngine_MR_impl.h.


Member Data Documentation

template<class GRAPH_T>
const mrpt_msgs::GraphSlamAgent mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::agent

GraphSlamAgent instance of the neighbor.

Note:
This should be an actual instance instead of a ref

Definition at line 208 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
std::string mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::cm_graph_service

Definition at line 259 of file CGraphSlamEngine_MR.h.

Definition at line 248 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
TColor mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::color

Unique color of current TNeighborAgentProps instance.

Definition at line 226 of file CGraphSlamEngine_MR.h.

Ref to the outer class.

Definition at line 203 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
mrpt::maps::COccupancyGridMap2D::Ptr mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::gridmap_cached [mutable]

Pointer to the gridmap object of the neighbor.

Definition at line 264 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::has_new_nodes [mutable]

Definition at line 266 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::has_new_scans [mutable]

Definition at line 267 of file CGraphSlamEngine_MR.h.

Definition at line 272 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
std::pair< TNodeID, mrpt::poses::CPose2D> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::last_integrated_pair_neighbor_frame

Last nodeID/CPose2D of neighbor that was integrated - Pose is taken with regards to neighbor's frame of reference.

Definition at line 284 of file CGraphSlamEngine_MR.h.

Definition at line 246 of file CGraphSlamEngine_MR.h.

Definition at line 257 of file CGraphSlamEngine_MR.h.

Definition at line 245 of file CGraphSlamEngine_MR.h.

Definition at line 256 of file CGraphSlamEngine_MR.h.

Definition at line 269 of file CGraphSlamEngine_MR.h.

NodeHandle passed by the calling CGraphSlamEngine_MR class.

Definition at line 271 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
std::map<TNodeID, bool> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::nodeID_to_is_integrated

Have I already integrated this node in my graph?

Note:
CGraphSlamEngine_MR instance is responsible of setting these values to true when it integrates them in own graph

Definition at line 240 of file CGraphSlamEngine_MR.h.

NodeIDs that I have received from this graphSLAM agent.

Definition at line 231 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
GRAPH_T::global_poses_t mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::poses

Poses that I have received from this graphSLAM agent.

Definition at line 233 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
std::vector<mrpt_msgs::NodeIDWithLaserScan> mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TNeighborAgentProps::ros_scans

ROS LaserScans that I have received from this graphSLAM agent.

Definition at line 235 of file CGraphSlamEngine_MR.h.

CPose2D connecting own graph origin to neighbor first received and integrated node. If this pose is 0 then it is not yet computed.

Definition at line 278 of file CGraphSlamEngine_MR.h.


The documentation for this struct was generated from the following files:


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Jun 6 2019 21:40:26