Swarm-SLAM
1.0.0
C-SLAM Framework
|
#include <rclcpp/rclcpp.hpp>
#include <gtsam/geometry/Pose3.h>
#include <gtsam/inference/Key.h>
#include <gtsam/inference/LabeledSymbol.h>
#include <gtsam/linear/NoiseModel.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/slam/BetweenFactor.h>
#include <cslam_common_interfaces/msg/pose_graph.hpp>
#include <cslam_common_interfaces/msg/pose_graph_edge.hpp>
#include <cslam_common_interfaces/msg/pose_graph_value.hpp>
#include <geometry_msgs/msg/transform.hpp>
#include <nav_msgs/msg/odometry.hpp>
Go to the source code of this file.
Namespaces | |
cslam | |
Macros | |
#define | GRAPH_LABEL 'g' |
#define | ROBOT_LABEL(id) ('A' + id) |
#define | ROBOT_ID(ch) ((unsigned int)(ch - 'A')) |
Functions | |
gtsam::Pose3 | cslam::odometry_msg_to_pose3 (const nav_msgs::msg::Odometry &odom_msg) |
Converts odometry message to gtsam::Pose3. More... | |
gtsam::Pose3 | cslam::transform_msg_to_pose3 (const geometry_msgs::msg::Transform &msg) |
Converts a transform msg into a gtsam::Pose3. More... | |
geometry_msgs::msg::Pose | cslam::gtsam_pose_to_msg (const gtsam::Pose3 &pose) |
Converts from GTSAM to ROS 2 message. More... | |
geometry_msgs::msg::Transform | cslam::gtsam_pose_to_transform_msg (const gtsam::Pose3 &pose) |
Converts from GTSAM to ROS 2 message. More... | |
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. More... | |
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. More... | |
std::vector< cslam_common_interfaces::msg::PoseGraphValue > | cslam::gtsam_values_to_msg (const gtsam::Values &values) |
Converts from GTSAM to ROS 2 message. More... | |
std::vector< cslam_common_interfaces::msg::PoseGraphEdge > | cslam::gtsam_factors_to_msg (const gtsam::NonlinearFactorGraph &factors) |
Converts from GTSAM to ROS 2 message. More... | |
gtsam::Pose3 | cslam::pose_msg_to_gtsam (const geometry_msgs::msg::Pose &pose) |
Converts from ROS 2 message to GTSAM. More... | |
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. More... | |
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. More... | |
#define GRAPH_LABEL 'g' |
Definition at line 20 of file gtsam_utils.h.
#define ROBOT_ID | ( | ch | ) | ((unsigned int)(ch - 'A')) |
Definition at line 22 of file gtsam_utils.h.
#define ROBOT_LABEL | ( | id | ) | ('A' + id) |
Definition at line 21 of file gtsam_utils.h.