Swarm-SLAM  1.0.0
C-SLAM Framework
cslam Namespace Reference

Namespaces

 algebraic_connectivity_maximization
 
 broker
 
 global_descriptor_loop_closure_detection
 
 lidar_handler_node
 
 loop_closure_detection_node
 
 loop_closure_sparse_matching
 
 neighbor_monitor
 
 neighbors_manager
 
 nns_matching
 

Classes

class  DecentralizedPGO
 
class  Logger
 
class  SimulatedRendezVous
 
class  IMapManager
 Map management interface class. More...
 
class  MapManager
 Loop Closure Detection Management. More...
 
class  RGBDHandler
 
class  ISensorHandler
 Interface class for handling sensor data. More...
 
class  StereoHandler
 

Enumerations

enum  OptimizerState {
  IDLE , WAITING_FOR_NEIGHBORS_INFO , POSEGRAPH_COLLECTION , WAITING_FOR_NEIGHBORS_POSEGRAPHS ,
  START_OPTIMIZATION , OPTIMIZATION
}
 State of the Pose Graph Optimization node. More...
 

Functions

gtsam::Pose3 odometry_msg_to_pose3 (const nav_msgs::msg::Odometry &odom_msg)
 Converts odometry message to gtsam::Pose3. More...
 
gtsam::Pose3 transform_msg_to_pose3 (const geometry_msgs::msg::Transform &msg)
 Converts a transform msg into a gtsam::Pose3. More...
 
geometry_msgs::msg::Pose gtsam_pose_to_msg (const gtsam::Pose3 &pose)
 Converts from GTSAM to ROS 2 message. More...
 
geometry_msgs::msg::Transform gtsam_pose_to_transform_msg (const gtsam::Pose3 &pose)
 Converts from GTSAM to ROS 2 message. More...
 
std::vector< cslam_common_interfaces::msg::PoseGraphValue > gtsam_values_to_msg (const gtsam::Values::shared_ptr values)
 Converts from GTSAM to ROS 2 message. More...
 
std::vector< cslam_common_interfaces::msg::PoseGraphEdge > gtsam_factors_to_msg (const gtsam::NonlinearFactorGraph::shared_ptr factors)
 Converts from GTSAM to ROS 2 message. More...
 
std::vector< cslam_common_interfaces::msg::PoseGraphValue > gtsam_values_to_msg (const gtsam::Values &values)
 Converts from GTSAM to ROS 2 message. More...
 
std::vector< cslam_common_interfaces::msg::PoseGraphEdge > gtsam_factors_to_msg (const gtsam::NonlinearFactorGraph &factors)
 Converts from GTSAM to ROS 2 message. More...
 
gtsam::Pose3 pose_msg_to_gtsam (const geometry_msgs::msg::Pose &pose)
 Converts from ROS 2 message to GTSAM. More...
 
gtsam::Values::shared_ptr values_msg_to_gtsam (const std::vector< cslam_common_interfaces::msg::PoseGraphValue > &values)
 Converts from ROS 2 message to GTSAM. More...
 
gtsam::NonlinearFactorGraph::shared_ptr edges_msg_to_gtsam (const std::vector< cslam_common_interfaces::msg::PoseGraphEdge > &edges)
 Converts from ROS 2 message to GTSAM. More...
 
sensor_msgs::msg::PointCloud2 create_colored_pointcloud (const std::shared_ptr< rtabmap::SensorData > &sensor_data, const std_msgs::msg::Header &header)
 Create a colored pointcloud message. More...
 
template<typename T >
void depth_image_to_pointcloud (const std::shared_ptr< rtabmap::SensorData > &sensor_data, sensor_msgs::msg::PointCloud2::SharedPtr &cloud_msg, const image_geometry::PinholeCameraModel &model, double range_max=0.0)
 Convert depth image to pointcloud. More...
 
void add_rgb_to_pointcloud (const std::shared_ptr< rtabmap::SensorData > &sensor_data, sensor_msgs::msg::PointCloud2::SharedPtr &cloud_msg)
 Add color to pointcloud. More...
 

Enumeration Type Documentation

◆ OptimizerState

State of the Pose Graph Optimization node.

IDLE: Do nothing. WAITING_FOR_NEIGHBORS_INFO: Wait for info on neighbors in range. POSEGRAPH_COLLECTION: Send request for neighboring robots pose graph WAITING_FOR_NEIGHBORS_POSEGRAPHS: Waits for neighboring robot pose graphs START_OPTIMIZATION: Triggers optimization process. OPTIMIZATION: While the pose graph optimization thresad is running.

Enumerator
IDLE 
WAITING_FOR_NEIGHBORS_INFO 
POSEGRAPH_COLLECTION 
WAITING_FOR_NEIGHBORS_POSEGRAPHS 
START_OPTIMIZATION 
OPTIMIZATION 

Definition at line 54 of file decentralized_pgo.h.

Function Documentation

◆ add_rgb_to_pointcloud()

void cslam::add_rgb_to_pointcloud ( const std::shared_ptr< rtabmap::SensorData > &  sensor_data,
sensor_msgs::msg::PointCloud2::SharedPtr &  cloud_msg 
)

Add color to pointcloud.

Parameters
sensor_data
cloud_msg

Definition at line 103 of file visualization_utils.cpp.

Here is the caller graph for this function:

◆ create_colored_pointcloud()

sensor_msgs::msg::PointCloud2 cslam::create_colored_pointcloud ( const std::shared_ptr< rtabmap::SensorData > &  sensor_data,
const std_msgs::msg::Header &  header 
)

Create a colored pointcloud message.

Parameters
sensor_datakeyframe data
headertimestamp + frame_id
Returns
sensor_msgs::msg::PointCloud2 message

Definition at line 8 of file visualization_utils.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ depth_image_to_pointcloud()

template<typename T >
void cslam::depth_image_to_pointcloud ( const std::shared_ptr< rtabmap::SensorData > &  sensor_data,
sensor_msgs::msg::PointCloud2::SharedPtr &  cloud_msg,
const image_geometry::PinholeCameraModel &  model,
double  range_max = 0.0 
)

Convert depth image to pointcloud.

Template Parameters
T
Parameters
sensor_data
cloud_msg
model
range_max

Definition at line 60 of file visualization_utils.cpp.

◆ edges_msg_to_gtsam()

gtsam::NonlinearFactorGraph::shared_ptr cslam::edges_msg_to_gtsam ( const std::vector< cslam_common_interfaces::msg::PoseGraphEdge > &  edges)

Converts from ROS 2 message to GTSAM.

Parameters
edges
Returns
gtsam::NonlinearFactorGraph::shared_ptr

Definition at line 126 of file gtsam_utils.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ gtsam_factors_to_msg() [1/2]

std::vector< cslam_common_interfaces::msg::PoseGraphEdge > cslam::gtsam_factors_to_msg ( const gtsam::NonlinearFactorGraph &  factors)

Converts from GTSAM to ROS 2 message.

Parameters
factors
Returns
std::vector<cslam_common_interfaces::msg::PoseGraphEdge>

Definition at line 59 of file gtsam_utils.cpp.

Here is the call graph for this function:

◆ gtsam_factors_to_msg() [2/2]

std::vector< cslam_common_interfaces::msg::PoseGraphEdge > cslam::gtsam_factors_to_msg ( const gtsam::NonlinearFactorGraph::shared_ptr  factors)

Converts from GTSAM to ROS 2 message.

Parameters
factors
Returns
std::vector<cslam_common_interfaces::msg::PoseGraphEdge>

Definition at line 92 of file gtsam_utils.cpp.

Here is the caller graph for this function:

◆ gtsam_pose_to_msg()

geometry_msgs::msg::Pose cslam::gtsam_pose_to_msg ( const gtsam::Pose3 &  pose)

Converts from GTSAM to ROS 2 message.

Parameters
pose
Returns
geometry_msgs::msg::Pose

Definition at line 5 of file gtsam_utils.cpp.

Here is the caller graph for this function:

◆ gtsam_pose_to_transform_msg()

geometry_msgs::msg::Transform cslam::gtsam_pose_to_transform_msg ( const gtsam::Pose3 &  pose)

Converts from GTSAM to ROS 2 message.

Parameters
pose
Returns
geometry_msgs::msg::Transform

Definition at line 19 of file gtsam_utils.cpp.

Here is the caller graph for this function:

◆ gtsam_values_to_msg() [1/2]

std::vector< cslam_common_interfaces::msg::PoseGraphValue > cslam::gtsam_values_to_msg ( const gtsam::Values &  values)

Converts from GTSAM to ROS 2 message.

Parameters
values
Returns
std::vector<cslam_common_interfaces::msg::PoseGraphValue>

Definition at line 35 of file gtsam_utils.cpp.

Here is the call graph for this function:

◆ gtsam_values_to_msg() [2/2]

std::vector< cslam_common_interfaces::msg::PoseGraphValue > cslam::gtsam_values_to_msg ( const gtsam::Values::shared_ptr  values)

Converts from GTSAM to ROS 2 message.

Parameters
values
Returns
std::vector<cslam_common_interfaces::msg::PoseGraphValue>

Definition at line 54 of file gtsam_utils.cpp.

Here is the caller graph for this function:

◆ odometry_msg_to_pose3()

gtsam::Pose3 cslam::odometry_msg_to_pose3 ( const nav_msgs::msg::Odometry &  odom_msg)

Converts odometry message to gtsam::Pose3.

Parameters
odom_msgOdometry message
Returns
pose Pose data

Definition at line 110 of file gtsam_utils.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pose_msg_to_gtsam()

gtsam::Pose3 cslam::pose_msg_to_gtsam ( const geometry_msgs::msg::Pose &  pose)

Converts from ROS 2 message to GTSAM.

Parameters
pose
Returns
gtsam::Pose3

Definition at line 103 of file gtsam_utils.cpp.

Here is the caller graph for this function:

◆ transform_msg_to_pose3()

gtsam::Pose3 cslam::transform_msg_to_pose3 ( const geometry_msgs::msg::Transform &  msg)

Converts a transform msg into a gtsam::Pose3.

Parameters
msgTransform message
Returns
pose Pose data

Definition at line 96 of file gtsam_utils.cpp.

Here is the caller graph for this function:

◆ values_msg_to_gtsam()

gtsam::Values::shared_ptr cslam::values_msg_to_gtsam ( const std::vector< cslam_common_interfaces::msg::PoseGraphValue > &  values)

Converts from ROS 2 message to GTSAM.

Parameters
values
Returns
gtsam::Values::shared_ptr

Definition at line 114 of file gtsam_utils.cpp.

Here is the call graph for this function:
Here is the caller graph for this function: