Uses scan matching to generate sequential and loop closure constraints. More...
#include <scan_match_constraints.h>
Public Member Functions | |
| ScanMatchConstraints (ros::NodeHandle param_nh, TfPtr tf) | |
Private Member Functions | |
| void | addConstraints (OptionalDiff diff, const pg::ConstraintGraph &g) |
| void | addSequenceLink (const unsigned n1, const unsigned n2) |
| tf::Pose | fixedFramePose (const unsigned n) const |
| Chain | getChain (const unsigned n, const pg::NodeSet &nodes, const pg::NodeSet &forbidden) const |
| ConstraintVec | getLoopConstraints (const unsigned n, const pg::ConstraintGraph &g, const gm::PoseStamped &l, const pg::NodeSet &running) const |
| ConstraintVec | getNearLinkConstraints (const unsigned n, const pg::ConstraintGraph &g, const gm::PoseStamped &l, const pg::NodeSet &running) const |
| ConstraintVec | getRunningConstraints (const unsigned n, const pg::ConstraintGraph &g, const gm::PoseStamped &l, const pg::NodeSet &running) const |
| pg::NodeSet | getRunningNodes (const pg::ConstraintGraph &g, const unsigned n, const gm::PoseStamped &l) const |
| void | locCallback (msg::LocalizationDistribution::ConstPtr m) |
| msg::GraphConstraint | makeConstraint (const pg::ConstraintGraph &g, const unsigned n, const unsigned ref, const karto_scan_matcher::ScanMatchResult &res, LocalizedScan::ConstPtr scan) const |
| msg::GraphConstraint | makeConstraint (const pg::ConstraintGraph &g, const unsigned n, const karto_scan_matcher::ScanMatchResult &res, const pg::NodeSet &nodes, LocalizedScan::ConstPtr scan) const |
| boost::optional< unsigned > | nextNode (const unsigned n) const |
| unsigned | nodeWithNearestBarycenter (const pg::ConstraintGraph &g, const pg::NodeSet &nodes, const geometry_msgs::Point &p) const |
| boost::optional< unsigned > | previousNode (const unsigned n) const |
| void | updateDistanceTravelled (const ros::TimerEvent &e) |
Private Attributes | |
| pose_graph::CachedNodeMap < std_msgs::UInt64 > | after_ |
| const std::string | base_frame_ |
| pose_graph::CachedNodeMap < std_msgs::UInt64 > | before_ |
| const double | chain_distance_threshold_ |
| ros::Publisher | constraint_pub_ |
| warehouse::WarehouseClient | db_ |
| pg::DiffSubscriber | diff_sub_ |
| double | distance_since_last_added_node_ |
| ros::Timer | distance_update_timer_ |
| pose_graph::CachedNodeMap < geometry_msgs::Pose > | ff_poses_ |
| const std::string | fixed_frame_ |
| ros::ServiceClient | get_poses_client_ |
| bool | initialized_ |
| const std::string | laser_frame_ |
| tf::Pose | laser_offset_ |
| boost::optional< unsigned > | last_added_node_ |
| graph_slam::LocalizationBuffer | loc_buf_ |
| ros::Subscriber | loc_sub_ |
| const double | local_window_size_ |
| const unsigned | loop_match_min_chain_size_ |
| const double | loop_match_window_size_ |
| MatcherPtr | loop_matcher_ |
| const double | loop_scan_match_res_ |
| const double | loop_scan_match_size_ |
| ros::Publisher | marker_pub_ |
| const double | max_loop_match_variance_ |
| const double | max_nbd_size_ |
| const double | min_loop_response_ |
| const double | min_sequential_response_ |
| boost::mutex | mutex_ |
| const unsigned | near_link_min_chain_size_ |
| ros::NodeHandle | nh_ |
| const std::string | opt_frame_ |
| pg::NodePoseMap | optimized_poses_ |
| ros::Publisher | pose_pub_ |
| const unsigned | running_buffer_size_ |
| boost::circular_buffer< unsigned > | running_nodes_ |
| const double | running_scan_match_res_ |
| const double | running_scan_match_size_ |
| ScanMap | scans_ |
| MatcherPtr | sequential_matcher_ |
| TfPtr | tf_ |
Uses scan matching to generate sequential and loop closure constraints.
Definition at line 66 of file scan_match_constraints.h.
| laser_slam::ScanMatchConstraints::ScanMatchConstraints | ( | ros::NodeHandle | param_nh, | |
| TfPtr | tf | |||
| ) |
Definition at line 47 of file odom_constraints.cpp.
| void laser_slam::ScanMatchConstraints::addConstraints | ( | OptionalDiff | diff, | |
| const pg::ConstraintGraph & | g | |||
| ) | [private] |
| void laser_slam::ScanMatchConstraints::addSequenceLink | ( | const unsigned | n1, | |
| const unsigned | n2 | |||
| ) | [private] |
Definition at line 505 of file odom_constraints.cpp.
| tf::Pose laser_slam::ScanMatchConstraints::fixedFramePose | ( | const unsigned | n | ) | const [private] |
Definition at line 234 of file odom_constraints.cpp.
| Chain laser_slam::ScanMatchConstraints::getChain | ( | const unsigned | n, | |
| const pg::NodeSet & | nodes, | |||
| const pg::NodeSet & | forbidden | |||
| ) | const [private] |
Definition at line 515 of file odom_constraints.cpp.
| ConstraintVec laser_slam::ScanMatchConstraints::getLoopConstraints | ( | const unsigned | n, | |
| const pg::ConstraintGraph & | g, | |||
| const gm::PoseStamped & | l, | |||
| const pg::NodeSet & | running | |||
| ) | const [private] |
Definition at line 292 of file odom_constraints.cpp.
| ConstraintVec laser_slam::ScanMatchConstraints::getNearLinkConstraints | ( | const unsigned | n, | |
| const pg::ConstraintGraph & | g, | |||
| const gm::PoseStamped & | l, | |||
| const pg::NodeSet & | running | |||
| ) | const [private] |
Definition at line 258 of file odom_constraints.cpp.
| ConstraintVec laser_slam::ScanMatchConstraints::getRunningConstraints | ( | const unsigned | n, | |
| const pg::ConstraintGraph & | g, | |||
| const gm::PoseStamped & | l, | |||
| const pg::NodeSet & | running | |||
| ) | const [private] |
Definition at line 378 of file odom_constraints.cpp.
| pg::NodeSet laser_slam::ScanMatchConstraints::getRunningNodes | ( | const pg::ConstraintGraph & | g, | |
| const unsigned | n, | |||
| const gm::PoseStamped & | l | |||
| ) | const [private] |
Definition at line 217 of file odom_constraints.cpp.
| void laser_slam::ScanMatchConstraints::locCallback | ( | msg::LocalizationDistribution::ConstPtr | m | ) | [private] |
Definition at line 100 of file odom_constraints.cpp.
| msg::GraphConstraint laser_slam::ScanMatchConstraints::makeConstraint | ( | const pg::ConstraintGraph & | g, | |
| const unsigned | n, | |||
| const unsigned | ref, | |||
| const karto_scan_matcher::ScanMatchResult & | res, | |||
| LocalizedScan::ConstPtr | scan | |||
| ) | const [private] |
| msg::GraphConstraint laser_slam::ScanMatchConstraints::makeConstraint | ( | const pg::ConstraintGraph & | g, | |
| const unsigned | n, | |||
| const karto_scan_matcher::ScanMatchResult & | res, | |||
| const pg::NodeSet & | nodes, | |||
| LocalizedScan::ConstPtr | scan | |||
| ) | const [private] |
| MaybeNode laser_slam::ScanMatchConstraints::nextNode | ( | const unsigned | n | ) | const [private] |
Definition at line 497 of file odom_constraints.cpp.
| unsigned laser_slam::ScanMatchConstraints::nodeWithNearestBarycenter | ( | const pg::ConstraintGraph & | g, | |
| const pg::NodeSet & | nodes, | |||
| const geometry_msgs::Point & | p | |||
| ) | const [private] |
| MaybeNode laser_slam::ScanMatchConstraints::previousNode | ( | const unsigned | n | ) | const [private] |
Definition at line 489 of file odom_constraints.cpp.
| void laser_slam::ScanMatchConstraints::updateDistanceTravelled | ( | const ros::TimerEvent & | e | ) | [private] |
Definition at line 239 of file odom_constraints.cpp.
pose_graph::CachedNodeMap<std_msgs::UInt64> laser_slam::ScanMatchConstraints::after_ [private] |
Definition at line 141 of file scan_match_constraints.h.
const std::string laser_slam::ScanMatchConstraints::base_frame_ [private] |
Definition at line 105 of file scan_match_constraints.h.
pose_graph::CachedNodeMap<std_msgs::UInt64> laser_slam::ScanMatchConstraints::before_ [private] |
Definition at line 141 of file scan_match_constraints.h.
const double laser_slam::ScanMatchConstraints::chain_distance_threshold_ [private] |
Definition at line 112 of file scan_match_constraints.h.
ros::Publisher laser_slam::ScanMatchConstraints::constraint_pub_ [private] |
Definition at line 148 of file scan_match_constraints.h.
warehouse::WarehouseClient laser_slam::ScanMatchConstraints::db_ [private] |
Definition at line 140 of file scan_match_constraints.h.
pg::DiffSubscriber laser_slam::ScanMatchConstraints::diff_sub_ [private] |
Definition at line 146 of file scan_match_constraints.h.
double laser_slam::ScanMatchConstraints::distance_since_last_added_node_ [private] |
Definition at line 130 of file scan_match_constraints.h.
ros::Timer laser_slam::ScanMatchConstraints::distance_update_timer_ [private] |
Definition at line 153 of file scan_match_constraints.h.
pose_graph::CachedNodeMap<geometry_msgs::Pose> laser_slam::ScanMatchConstraints::ff_poses_ [private] |
Definition at line 143 of file scan_match_constraints.h.
const std::string laser_slam::ScanMatchConstraints::fixed_frame_ [private] |
Definition at line 104 of file scan_match_constraints.h.
ros::ServiceClient laser_slam::ScanMatchConstraints::get_poses_client_ [private] |
Definition at line 150 of file scan_match_constraints.h.
bool laser_slam::ScanMatchConstraints::initialized_ [private] |
Definition at line 128 of file scan_match_constraints.h.
const std::string laser_slam::ScanMatchConstraints::laser_frame_ [private] |
Definition at line 106 of file scan_match_constraints.h.
tf::Pose laser_slam::ScanMatchConstraints::laser_offset_ [private] |
Definition at line 122 of file scan_match_constraints.h.
boost::optional<unsigned> laser_slam::ScanMatchConstraints::last_added_node_ [private] |
Definition at line 129 of file scan_match_constraints.h.
graph_slam::LocalizationBuffer laser_slam::ScanMatchConstraints::loc_buf_ [private] |
Definition at line 144 of file scan_match_constraints.h.
ros::Subscriber laser_slam::ScanMatchConstraints::loc_sub_ [private] |
Definition at line 147 of file scan_match_constraints.h.
const double laser_slam::ScanMatchConstraints::local_window_size_ [private] |
Definition at line 108 of file scan_match_constraints.h.
const unsigned laser_slam::ScanMatchConstraints::loop_match_min_chain_size_ [private] |
Definition at line 116 of file scan_match_constraints.h.
const double laser_slam::ScanMatchConstraints::loop_match_window_size_ [private] |
Definition at line 115 of file scan_match_constraints.h.
Definition at line 152 of file scan_match_constraints.h.
const double laser_slam::ScanMatchConstraints::loop_scan_match_res_ [private] |
Definition at line 114 of file scan_match_constraints.h.
const double laser_slam::ScanMatchConstraints::loop_scan_match_size_ [private] |
Definition at line 113 of file scan_match_constraints.h.
ros::Publisher laser_slam::ScanMatchConstraints::marker_pub_ [private] |
Definition at line 149 of file scan_match_constraints.h.
const double laser_slam::ScanMatchConstraints::max_loop_match_variance_ [private] |
Definition at line 118 of file scan_match_constraints.h.
const double laser_slam::ScanMatchConstraints::max_nbd_size_ [private] |
Definition at line 120 of file scan_match_constraints.h.
const double laser_slam::ScanMatchConstraints::min_loop_response_ [private] |
Definition at line 117 of file scan_match_constraints.h.
const double laser_slam::ScanMatchConstraints::min_sequential_response_ [private] |
Definition at line 119 of file scan_match_constraints.h.
boost::mutex laser_slam::ScanMatchConstraints::mutex_ [private] |
Definition at line 138 of file scan_match_constraints.h.
const unsigned laser_slam::ScanMatchConstraints::near_link_min_chain_size_ [private] |
Definition at line 111 of file scan_match_constraints.h.
ros::NodeHandle laser_slam::ScanMatchConstraints::nh_ [private] |
Definition at line 145 of file scan_match_constraints.h.
const std::string laser_slam::ScanMatchConstraints::opt_frame_ [private] |
Definition at line 107 of file scan_match_constraints.h.
pg::NodePoseMap laser_slam::ScanMatchConstraints::optimized_poses_ [private] |
Definition at line 132 of file scan_match_constraints.h.
ros::Publisher laser_slam::ScanMatchConstraints::pose_pub_ [private] |
Definition at line 149 of file scan_match_constraints.h.
const unsigned laser_slam::ScanMatchConstraints::running_buffer_size_ [private] |
Definition at line 121 of file scan_match_constraints.h.
boost::circular_buffer<unsigned> laser_slam::ScanMatchConstraints::running_nodes_ [private] |
Definition at line 131 of file scan_match_constraints.h.
const double laser_slam::ScanMatchConstraints::running_scan_match_res_ [private] |
Definition at line 110 of file scan_match_constraints.h.
const double laser_slam::ScanMatchConstraints::running_scan_match_size_ [private] |
Definition at line 109 of file scan_match_constraints.h.
Definition at line 142 of file scan_match_constraints.h.
Definition at line 151 of file scan_match_constraints.h.
TfPtr laser_slam::ScanMatchConstraints::tf_ [private] |
Definition at line 139 of file scan_match_constraints.h.