Public Member Functions | Private Member Functions | Private Attributes | List of all members
scan_tools::LaserScanMatcher Class Reference

#include <laser_scan_matcher.h>

Public Member Functions

 LaserScanMatcher (ros::NodeHandle nh, ros::NodeHandle nh_private)
 
 ~LaserScanMatcher ()
 

Private Member Functions

void addOdomToHistory (const nav_msgs::Odometry::ConstPtr &o)
 
void constructedScanToLDP (LDP &ldp)
 
void constructScan (const ros::Time &timestamp)
 
void createTfFromXYTheta (double x, double y, double theta, tf::Transform &t)
 
void doPredictPose (double delta_t)
 
void doPublishDebugTF (const ros::Time &time, const tf::Transform &odom_delta, const ros::Publisher &publisher, const std::string &frame)
 
void doPublishOdomRate (const ros::Time &time)
 
void doPublishScanRate (const ros::Time &time)
 
nav_msgs::OdometryearliestOdomAfter (const ros::Time &time)
 
tf::Vector3 fusePoses (const tf::Transform &pose_delta)
 
bool getBaseToFootprintTf (const std::string &frame_id)
 
bool getBaseToLaserTf (const std::string &frame_id)
 
double getOdomDeltaT (const nav_msgs::Odometry::ConstPtr &o)
 
void getPrediction (double &pr_ch_x, double &pr_ch_y, double &pr_ch_a, double dt)
 
void initialposeCallback (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &pose_msg)
 
void initParams ()
 
void laserScanToLDP (const sensor_msgs::LaserScan::ConstPtr &scan_msg, LDP &ldp)
 
nav_msgs::OdometrylatestOdomBefore (const ros::Time &time)
 
void mapCallback (const nav_msgs::OccupancyGrid::ConstPtr &map_msg)
 
bool newKeyframeNeeded (const tf::Transform &d)
 
void odomCallback (const nav_msgs::Odometry::ConstPtr &odom_msg)
 
int processScan (LDP &curr_ldp_scan, const ros::Time &time)
 
int processScan (LDP &curr_ldp_scan, LDP &ref_ldp_scan, const ros::Time &time)
 
void resetState ()
 
void scanCallback (const sensor_msgs::LaserScan::ConstPtr &scan_msg)
 
void setTransSigmaMatrix (const double yaw)
 
double syncOdom (const ros::Time &time)
 

Private Attributes

gsl_matrix * B_odom_
 
std::string base_frame_
 
tf::Transform base_to_footprint_
 
tf::Transform base_to_laser_
 
std::vector< double > constructed_intensities_
 
std::vector< double > constructed_ranges_
 
ros::Publisher constructed_scan_publisher_
 
nav_msgs::Odometry current_odom_msg_
 
bool debug_csm_
 
ros::Publisher debug_laser_delta_publisher_
 
ros::Publisher debug_odom_current_publisher_
 
ros::Publisher debug_odom_delta_publisher_
 
ros::Publisher debug_odom_reference_publisher_
 
tf::Transform f2b_
 
tf::Transform f2b_kf_
 
tf::Transform f2pcl_
 
std::string fixed_frame_
 
tf::Transform footprint_to_base_
 
bool have_map_
 
gsl_matrix * I1_
 
gsl_matrix * I2_
 
tf::Transform initial_pose_
 
bool initialized_
 
ros::Subscriber initialpose_subscriber_
 
std::string initialpose_topic_
 
bool initialpose_valid_
 
sm_params input_
 
gsl_matrix * kalman_gain_
 
gsl_matrix * kalman_gain_comp_
 
double kf_dist_angular_
 
double kf_dist_linear_
 
double kf_dist_linear_sq_
 
tf::Transform laser_to_base_
 
ros::Time last_icp_time_
 
double map_occupancy_threshold_
 
ros::Subscriber map_subscriber_
 
double max_allowed_range_
 
double max_pose_delta_yaw_
 
double max_variance_rot_
 
double max_variance_trans_
 
tf::Transform measured_pose_
 
ros::Publisher measured_pose_publisher_
 
boost::mutex mutex_
 
ros::NodeHandle nh_
 
ros::NodeHandle nh_private_
 
bool no_odom_fusing_
 
double observed_angle_inc_
 
double observed_angle_max_
 
double observed_angle_min_
 
double observed_range_max_
 
double observed_range_min_
 
std::string observed_scan_frame_
 
double observed_scan_time_
 
double observed_time_inc_
 
std::string odom_frame_
 
std::deque< nav_msgs::Odometryodom_history_
 
ros::Subscriber odom_subscriber_
 
std::vector< double > orientation_covariance_
 
sm_result output_
 
gsl_permutation * P2_
 
tf::Transform pcl2f_
 
ros::Publisher pose_publisher_
 
ros::Publisher pose_stamped_publisher_
 
ros::Publisher pose_with_covariance_publisher_
 
ros::Publisher pose_with_covariance_stamped_publisher_
 
std::vector< double > position_covariance_
 
tf::Transform predicted_pose_
 
tf::Transform predicted_pose_in_pcl_
 
ros::Publisher predicted_pose_publisher_
 
LDP prev_ldp_scan_
 
bool publish_base_tf_
 
bool publish_constructed_scan_
 
bool publish_debug_
 
bool publish_measured_pose_
 
bool publish_odom_tf_
 
bool publish_pose_
 
bool publish_pose_stamped_
 
bool publish_pose_with_covariance_
 
bool publish_pose_with_covariance_stamped_
 
bool publish_predicted_pose_
 
bool received_odom_
 
nav_msgs::Odometry reference_odom_msg_
 
ScanConstructor scan_constructor_
 
int scan_downsample_rate_
 
ros::Subscriber scan_subscriber_
 
gsl_matrix * Sigma_measured_
 
gsl_matrix * Sigma_odom_
 
gsl_matrix * Sigma_odom_trans_
 
gsl_matrix * Sigma_u_
 
int skipped_poses_
 
tf::TransformBroadcaster tf_broadcaster_
 
tf::TransformListener tf_listener_
 
double theta_odom_
 
gsl_matrix * trans_sigma_
 
bool use_map_
 
bool use_odom_
 
gsl_vector * xvec_
 
gsl_vector * yvec_
 

Detailed Description

Definition at line 75 of file laser_scan_matcher.h.

Constructor & Destructor Documentation

◆ LaserScanMatcher()

scan_tools::LaserScanMatcher::LaserScanMatcher ( ros::NodeHandle  nh,
ros::NodeHandle  nh_private 
)

Definition at line 50 of file laser_scan_matcher.cpp.

◆ ~LaserScanMatcher()

scan_tools::LaserScanMatcher::~LaserScanMatcher ( )

Definition at line 171 of file laser_scan_matcher.cpp.

Member Function Documentation

◆ addOdomToHistory()

void scan_tools::LaserScanMatcher::addOdomToHistory ( const nav_msgs::Odometry::ConstPtr &  o)
private

Definition at line 439 of file laser_scan_matcher.cpp.

◆ constructedScanToLDP()

void scan_tools::LaserScanMatcher::constructedScanToLDP ( LDP ldp)
private

Definition at line 1265 of file laser_scan_matcher.cpp.

◆ constructScan()

void scan_tools::LaserScanMatcher::constructScan ( const ros::Time timestamp)
private

Definition at line 588 of file laser_scan_matcher.cpp.

◆ createTfFromXYTheta()

void scan_tools::LaserScanMatcher::createTfFromXYTheta ( double  x,
double  y,
double  theta,
tf::Transform t 
)
private

Definition at line 1370 of file laser_scan_matcher.cpp.

◆ doPredictPose()

void scan_tools::LaserScanMatcher::doPredictPose ( double  delta_t)
private

Definition at line 491 of file laser_scan_matcher.cpp.

◆ doPublishDebugTF()

void scan_tools::LaserScanMatcher::doPublishDebugTF ( const ros::Time time,
const tf::Transform odom_delta,
const ros::Publisher publisher,
const std::string &  frame 
)
private

Definition at line 798 of file laser_scan_matcher.cpp.

◆ doPublishOdomRate()

void scan_tools::LaserScanMatcher::doPublishOdomRate ( const ros::Time time)
private

Definition at line 808 of file laser_scan_matcher.cpp.

◆ doPublishScanRate()

void scan_tools::LaserScanMatcher::doPublishScanRate ( const ros::Time time)
private

Definition at line 830 of file laser_scan_matcher.cpp.

◆ earliestOdomAfter()

nav_msgs::Odometry * scan_tools::LaserScanMatcher::earliestOdomAfter ( const ros::Time time)
private

Definition at line 420 of file laser_scan_matcher.cpp.

◆ fusePoses()

tf::Vector3 scan_tools::LaserScanMatcher::fusePoses ( const tf::Transform pose_delta)
private

Definition at line 926 of file laser_scan_matcher.cpp.

◆ getBaseToFootprintTf()

bool scan_tools::LaserScanMatcher::getBaseToFootprintTf ( const std::string &  frame_id)
private

Definition at line 1314 of file laser_scan_matcher.cpp.

◆ getBaseToLaserTf()

bool scan_tools::LaserScanMatcher::getBaseToLaserTf ( const std::string &  frame_id)
private

Definition at line 1291 of file laser_scan_matcher.cpp.

◆ getOdomDeltaT()

double scan_tools::LaserScanMatcher::getOdomDeltaT ( const nav_msgs::Odometry::ConstPtr &  o)
private

Definition at line 484 of file laser_scan_matcher.cpp.

◆ getPrediction()

void scan_tools::LaserScanMatcher::getPrediction ( double &  pr_ch_x,
double &  pr_ch_y,
double &  pr_ch_a,
double  dt 
)
private

Definition at line 1339 of file laser_scan_matcher.cpp.

◆ initialposeCallback()

void scan_tools::LaserScanMatcher::initialposeCallback ( const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &  pose_msg)
private

Definition at line 640 of file laser_scan_matcher.cpp.

◆ initParams()

void scan_tools::LaserScanMatcher::initParams ( )
private

Definition at line 212 of file laser_scan_matcher.cpp.

◆ laserScanToLDP()

void scan_tools::LaserScanMatcher::laserScanToLDP ( const sensor_msgs::LaserScan::ConstPtr &  scan_msg,
LDP ldp 
)
private

Definition at line 1222 of file laser_scan_matcher.cpp.

◆ latestOdomBefore()

nav_msgs::Odometry * scan_tools::LaserScanMatcher::latestOdomBefore ( const ros::Time time)
private

Definition at line 411 of file laser_scan_matcher.cpp.

◆ mapCallback()

void scan_tools::LaserScanMatcher::mapCallback ( const nav_msgs::OccupancyGrid::ConstPtr &  map_msg)
private

Definition at line 685 of file laser_scan_matcher.cpp.

◆ newKeyframeNeeded()

bool scan_tools::LaserScanMatcher::newKeyframeNeeded ( const tf::Transform d)
private

Definition at line 1211 of file laser_scan_matcher.cpp.

◆ odomCallback()

void scan_tools::LaserScanMatcher::odomCallback ( const nav_msgs::Odometry::ConstPtr &  odom_msg)
private

Definition at line 553 of file laser_scan_matcher.cpp.

◆ processScan() [1/2]

int scan_tools::LaserScanMatcher::processScan ( LDP curr_ldp_scan,
const ros::Time time 
)
private

Definition at line 1095 of file laser_scan_matcher.cpp.

◆ processScan() [2/2]

int scan_tools::LaserScanMatcher::processScan ( LDP curr_ldp_scan,
LDP ref_ldp_scan,
const ros::Time time 
)
private

Definition at line 978 of file laser_scan_matcher.cpp.

◆ resetState()

void scan_tools::LaserScanMatcher::resetState ( )
private

Definition at line 188 of file laser_scan_matcher.cpp.

◆ scanCallback()

void scan_tools::LaserScanMatcher::scanCallback ( const sensor_msgs::LaserScan::ConstPtr &  scan_msg)
private

Definition at line 721 of file laser_scan_matcher.cpp.

◆ setTransSigmaMatrix()

void scan_tools::LaserScanMatcher::setTransSigmaMatrix ( const double  yaw)
private

Definition at line 580 of file laser_scan_matcher.cpp.

◆ syncOdom()

double scan_tools::LaserScanMatcher::syncOdom ( const ros::Time time)
private

Definition at line 446 of file laser_scan_matcher.cpp.

Member Data Documentation

◆ B_odom_

gsl_matrix* scan_tools::LaserScanMatcher::B_odom_
private

Definition at line 190 of file laser_scan_matcher.h.

◆ base_frame_

std::string scan_tools::LaserScanMatcher::base_frame_
private

Definition at line 116 of file laser_scan_matcher.h.

◆ base_to_footprint_

tf::Transform scan_tools::LaserScanMatcher::base_to_footprint_
private

Definition at line 98 of file laser_scan_matcher.h.

◆ base_to_laser_

tf::Transform scan_tools::LaserScanMatcher::base_to_laser_
private

Definition at line 96 of file laser_scan_matcher.h.

◆ constructed_intensities_

std::vector<double> scan_tools::LaserScanMatcher::constructed_intensities_
private

Definition at line 182 of file laser_scan_matcher.h.

◆ constructed_ranges_

std::vector<double> scan_tools::LaserScanMatcher::constructed_ranges_
private

Definition at line 183 of file laser_scan_matcher.h.

◆ constructed_scan_publisher_

ros::Publisher scan_tools::LaserScanMatcher::constructed_scan_publisher_
private

Definition at line 107 of file laser_scan_matcher.h.

◆ current_odom_msg_

nav_msgs::Odometry scan_tools::LaserScanMatcher::current_odom_msg_
private

Definition at line 179 of file laser_scan_matcher.h.

◆ debug_csm_

bool scan_tools::LaserScanMatcher::debug_csm_
private

Definition at line 138 of file laser_scan_matcher.h.

◆ debug_laser_delta_publisher_

ros::Publisher scan_tools::LaserScanMatcher::debug_laser_delta_publisher_
private

Definition at line 110 of file laser_scan_matcher.h.

◆ debug_odom_current_publisher_

ros::Publisher scan_tools::LaserScanMatcher::debug_odom_current_publisher_
private

Definition at line 112 of file laser_scan_matcher.h.

◆ debug_odom_delta_publisher_

ros::Publisher scan_tools::LaserScanMatcher::debug_odom_delta_publisher_
private

Definition at line 109 of file laser_scan_matcher.h.

◆ debug_odom_reference_publisher_

ros::Publisher scan_tools::LaserScanMatcher::debug_odom_reference_publisher_
private

Definition at line 111 of file laser_scan_matcher.h.

◆ f2b_

tf::Transform scan_tools::LaserScanMatcher::f2b_
private

Definition at line 174 of file laser_scan_matcher.h.

◆ f2b_kf_

tf::Transform scan_tools::LaserScanMatcher::f2b_kf_
private

Definition at line 175 of file laser_scan_matcher.h.

◆ f2pcl_

tf::Transform scan_tools::LaserScanMatcher::f2pcl_
private

Definition at line 171 of file laser_scan_matcher.h.

◆ fixed_frame_

std::string scan_tools::LaserScanMatcher::fixed_frame_
private

Definition at line 117 of file laser_scan_matcher.h.

◆ footprint_to_base_

tf::Transform scan_tools::LaserScanMatcher::footprint_to_base_
private

Definition at line 99 of file laser_scan_matcher.h.

◆ have_map_

bool scan_tools::LaserScanMatcher::have_map_
private

Definition at line 154 of file laser_scan_matcher.h.

◆ I1_

gsl_matrix* scan_tools::LaserScanMatcher::I1_
private

Definition at line 192 of file laser_scan_matcher.h.

◆ I2_

gsl_matrix* scan_tools::LaserScanMatcher::I2_
private

Definition at line 193 of file laser_scan_matcher.h.

◆ initial_pose_

tf::Transform scan_tools::LaserScanMatcher::initial_pose_
private

Definition at line 170 of file laser_scan_matcher.h.

◆ initialized_

bool scan_tools::LaserScanMatcher::initialized_
private

Definition at line 153 of file laser_scan_matcher.h.

◆ initialpose_subscriber_

ros::Subscriber scan_tools::LaserScanMatcher::initialpose_subscriber_
private

Definition at line 91 of file laser_scan_matcher.h.

◆ initialpose_topic_

std::string scan_tools::LaserScanMatcher::initialpose_topic_
private

Definition at line 119 of file laser_scan_matcher.h.

◆ initialpose_valid_

bool scan_tools::LaserScanMatcher::initialpose_valid_
private

Definition at line 127 of file laser_scan_matcher.h.

◆ input_

sm_params scan_tools::LaserScanMatcher::input_
private

Definition at line 202 of file laser_scan_matcher.h.

◆ kalman_gain_

gsl_matrix* scan_tools::LaserScanMatcher::kalman_gain_
private

Definition at line 196 of file laser_scan_matcher.h.

◆ kalman_gain_comp_

gsl_matrix* scan_tools::LaserScanMatcher::kalman_gain_comp_
private

Definition at line 197 of file laser_scan_matcher.h.

◆ kf_dist_angular_

double scan_tools::LaserScanMatcher::kf_dist_angular_
private

Definition at line 144 of file laser_scan_matcher.h.

◆ kf_dist_linear_

double scan_tools::LaserScanMatcher::kf_dist_linear_
private

Definition at line 142 of file laser_scan_matcher.h.

◆ kf_dist_linear_sq_

double scan_tools::LaserScanMatcher::kf_dist_linear_sq_
private

Definition at line 143 of file laser_scan_matcher.h.

◆ laser_to_base_

tf::Transform scan_tools::LaserScanMatcher::laser_to_base_
private

Definition at line 97 of file laser_scan_matcher.h.

◆ last_icp_time_

ros::Time scan_tools::LaserScanMatcher::last_icp_time_
private

Definition at line 177 of file laser_scan_matcher.h.

◆ map_occupancy_threshold_

double scan_tools::LaserScanMatcher::map_occupancy_threshold_
private

Definition at line 125 of file laser_scan_matcher.h.

◆ map_subscriber_

ros::Subscriber scan_tools::LaserScanMatcher::map_subscriber_
private

Definition at line 89 of file laser_scan_matcher.h.

◆ max_allowed_range_

double scan_tools::LaserScanMatcher::max_allowed_range_
private

Definition at line 123 of file laser_scan_matcher.h.

◆ max_pose_delta_yaw_

double scan_tools::LaserScanMatcher::max_pose_delta_yaw_
private

Definition at line 124 of file laser_scan_matcher.h.

◆ max_variance_rot_

double scan_tools::LaserScanMatcher::max_variance_rot_
private

Definition at line 122 of file laser_scan_matcher.h.

◆ max_variance_trans_

double scan_tools::LaserScanMatcher::max_variance_trans_
private

Definition at line 121 of file laser_scan_matcher.h.

◆ measured_pose_

tf::Transform scan_tools::LaserScanMatcher::measured_pose_
private

Definition at line 168 of file laser_scan_matcher.h.

◆ measured_pose_publisher_

ros::Publisher scan_tools::LaserScanMatcher::measured_pose_publisher_
private

Definition at line 106 of file laser_scan_matcher.h.

◆ mutex_

boost::mutex scan_tools::LaserScanMatcher::mutex_
private

Definition at line 151 of file laser_scan_matcher.h.

◆ nh_

ros::NodeHandle scan_tools::LaserScanMatcher::nh_
private

Definition at line 85 of file laser_scan_matcher.h.

◆ nh_private_

ros::NodeHandle scan_tools::LaserScanMatcher::nh_private_
private

Definition at line 86 of file laser_scan_matcher.h.

◆ no_odom_fusing_

bool scan_tools::LaserScanMatcher::no_odom_fusing_
private

Definition at line 147 of file laser_scan_matcher.h.

◆ observed_angle_inc_

double scan_tools::LaserScanMatcher::observed_angle_inc_
private

Definition at line 161 of file laser_scan_matcher.h.

◆ observed_angle_max_

double scan_tools::LaserScanMatcher::observed_angle_max_
private

Definition at line 160 of file laser_scan_matcher.h.

◆ observed_angle_min_

double scan_tools::LaserScanMatcher::observed_angle_min_
private

Definition at line 159 of file laser_scan_matcher.h.

◆ observed_range_max_

double scan_tools::LaserScanMatcher::observed_range_max_
private

Definition at line 158 of file laser_scan_matcher.h.

◆ observed_range_min_

double scan_tools::LaserScanMatcher::observed_range_min_
private

Definition at line 157 of file laser_scan_matcher.h.

◆ observed_scan_frame_

std::string scan_tools::LaserScanMatcher::observed_scan_frame_
private

Definition at line 164 of file laser_scan_matcher.h.

◆ observed_scan_time_

double scan_tools::LaserScanMatcher::observed_scan_time_
private

Definition at line 162 of file laser_scan_matcher.h.

◆ observed_time_inc_

double scan_tools::LaserScanMatcher::observed_time_inc_
private

Definition at line 163 of file laser_scan_matcher.h.

◆ odom_frame_

std::string scan_tools::LaserScanMatcher::odom_frame_
private

Definition at line 118 of file laser_scan_matcher.h.

◆ odom_history_

std::deque<nav_msgs::Odometry> scan_tools::LaserScanMatcher::odom_history_
private

Definition at line 184 of file laser_scan_matcher.h.

◆ odom_subscriber_

ros::Subscriber scan_tools::LaserScanMatcher::odom_subscriber_
private

Definition at line 90 of file laser_scan_matcher.h.

◆ orientation_covariance_

std::vector<double> scan_tools::LaserScanMatcher::orientation_covariance_
private

Definition at line 140 of file laser_scan_matcher.h.

◆ output_

sm_result scan_tools::LaserScanMatcher::output_
private

Definition at line 203 of file laser_scan_matcher.h.

◆ P2_

gsl_permutation* scan_tools::LaserScanMatcher::P2_
private

Definition at line 194 of file laser_scan_matcher.h.

◆ pcl2f_

tf::Transform scan_tools::LaserScanMatcher::pcl2f_
private

Definition at line 172 of file laser_scan_matcher.h.

◆ pose_publisher_

ros::Publisher scan_tools::LaserScanMatcher::pose_publisher_
private

Definition at line 101 of file laser_scan_matcher.h.

◆ pose_stamped_publisher_

ros::Publisher scan_tools::LaserScanMatcher::pose_stamped_publisher_
private

Definition at line 102 of file laser_scan_matcher.h.

◆ pose_with_covariance_publisher_

ros::Publisher scan_tools::LaserScanMatcher::pose_with_covariance_publisher_
private

Definition at line 103 of file laser_scan_matcher.h.

◆ pose_with_covariance_stamped_publisher_

ros::Publisher scan_tools::LaserScanMatcher::pose_with_covariance_stamped_publisher_
private

Definition at line 104 of file laser_scan_matcher.h.

◆ position_covariance_

std::vector<double> scan_tools::LaserScanMatcher::position_covariance_
private

Definition at line 139 of file laser_scan_matcher.h.

◆ predicted_pose_

tf::Transform scan_tools::LaserScanMatcher::predicted_pose_
private

Definition at line 167 of file laser_scan_matcher.h.

◆ predicted_pose_in_pcl_

tf::Transform scan_tools::LaserScanMatcher::predicted_pose_in_pcl_
private

Definition at line 169 of file laser_scan_matcher.h.

◆ predicted_pose_publisher_

ros::Publisher scan_tools::LaserScanMatcher::predicted_pose_publisher_
private

Definition at line 105 of file laser_scan_matcher.h.

◆ prev_ldp_scan_

LDP scan_tools::LaserScanMatcher::prev_ldp_scan_
private

Definition at line 204 of file laser_scan_matcher.h.

◆ publish_base_tf_

bool scan_tools::LaserScanMatcher::publish_base_tf_
private

Definition at line 129 of file laser_scan_matcher.h.

◆ publish_constructed_scan_

bool scan_tools::LaserScanMatcher::publish_constructed_scan_
private

Definition at line 128 of file laser_scan_matcher.h.

◆ publish_debug_

bool scan_tools::LaserScanMatcher::publish_debug_
private

Definition at line 137 of file laser_scan_matcher.h.

◆ publish_measured_pose_

bool scan_tools::LaserScanMatcher::publish_measured_pose_
private

Definition at line 136 of file laser_scan_matcher.h.

◆ publish_odom_tf_

bool scan_tools::LaserScanMatcher::publish_odom_tf_
private

Definition at line 130 of file laser_scan_matcher.h.

◆ publish_pose_

bool scan_tools::LaserScanMatcher::publish_pose_
private

Definition at line 131 of file laser_scan_matcher.h.

◆ publish_pose_stamped_

bool scan_tools::LaserScanMatcher::publish_pose_stamped_
private

Definition at line 133 of file laser_scan_matcher.h.

◆ publish_pose_with_covariance_

bool scan_tools::LaserScanMatcher::publish_pose_with_covariance_
private

Definition at line 132 of file laser_scan_matcher.h.

◆ publish_pose_with_covariance_stamped_

bool scan_tools::LaserScanMatcher::publish_pose_with_covariance_stamped_
private

Definition at line 134 of file laser_scan_matcher.h.

◆ publish_predicted_pose_

bool scan_tools::LaserScanMatcher::publish_predicted_pose_
private

Definition at line 135 of file laser_scan_matcher.h.

◆ received_odom_

bool scan_tools::LaserScanMatcher::received_odom_
private

Definition at line 155 of file laser_scan_matcher.h.

◆ reference_odom_msg_

nav_msgs::Odometry scan_tools::LaserScanMatcher::reference_odom_msg_
private

Definition at line 180 of file laser_scan_matcher.h.

◆ scan_constructor_

ScanConstructor scan_tools::LaserScanMatcher::scan_constructor_
private

Definition at line 156 of file laser_scan_matcher.h.

◆ scan_downsample_rate_

int scan_tools::LaserScanMatcher::scan_downsample_rate_
private

Definition at line 120 of file laser_scan_matcher.h.

◆ scan_subscriber_

ros::Subscriber scan_tools::LaserScanMatcher::scan_subscriber_
private

Definition at line 88 of file laser_scan_matcher.h.

◆ Sigma_measured_

gsl_matrix* scan_tools::LaserScanMatcher::Sigma_measured_
private

Definition at line 189 of file laser_scan_matcher.h.

◆ Sigma_odom_

gsl_matrix* scan_tools::LaserScanMatcher::Sigma_odom_
private

Definition at line 187 of file laser_scan_matcher.h.

◆ Sigma_odom_trans_

gsl_matrix* scan_tools::LaserScanMatcher::Sigma_odom_trans_
private

Definition at line 188 of file laser_scan_matcher.h.

◆ Sigma_u_

gsl_matrix* scan_tools::LaserScanMatcher::Sigma_u_
private

Definition at line 191 of file laser_scan_matcher.h.

◆ skipped_poses_

int scan_tools::LaserScanMatcher::skipped_poses_
private

Definition at line 165 of file laser_scan_matcher.h.

◆ tf_broadcaster_

tf::TransformBroadcaster scan_tools::LaserScanMatcher::tf_broadcaster_
private

Definition at line 94 of file laser_scan_matcher.h.

◆ tf_listener_

tf::TransformListener scan_tools::LaserScanMatcher::tf_listener_
private

Definition at line 93 of file laser_scan_matcher.h.

◆ theta_odom_

double scan_tools::LaserScanMatcher::theta_odom_
private

Definition at line 200 of file laser_scan_matcher.h.

◆ trans_sigma_

gsl_matrix* scan_tools::LaserScanMatcher::trans_sigma_
private

Definition at line 195 of file laser_scan_matcher.h.

◆ use_map_

bool scan_tools::LaserScanMatcher::use_map_
private

Definition at line 126 of file laser_scan_matcher.h.

◆ use_odom_

bool scan_tools::LaserScanMatcher::use_odom_
private

Definition at line 146 of file laser_scan_matcher.h.

◆ xvec_

gsl_vector* scan_tools::LaserScanMatcher::xvec_
private

Definition at line 198 of file laser_scan_matcher.h.

◆ yvec_

gsl_vector* scan_tools::LaserScanMatcher::yvec_
private

Definition at line 199 of file laser_scan_matcher.h.


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


lsm_localization
Author(s): Ivan Dryanovski , Ilija Hadzic
autogenerated on Fri Dec 23 2022 03:09:11