#include <laser_scan_matcher.h>
Definition at line 65 of file laser_scan_matcher.h.
scan_tools::LaserScanMatcher::~LaserScanMatcher |
( |
| ) |
|
void scan_tools::LaserScanMatcher::cloudCallback |
( |
const PointCloudT::ConstPtr & |
cloud | ) |
|
|
private |
void scan_tools::LaserScanMatcher::createCache |
( |
const sensor_msgs::LaserScan::ConstPtr & |
scan_msg | ) |
|
|
private |
void scan_tools::LaserScanMatcher::createTfFromXYTheta |
( |
double |
x, |
|
|
double |
y, |
|
|
double |
theta, |
|
|
tf::Transform & |
t |
|
) |
| |
|
private |
bool scan_tools::LaserScanMatcher::getBaseToLaserTf |
( |
const std::string & |
frame_id | ) |
|
|
private |
void scan_tools::LaserScanMatcher::getPrediction |
( |
double & |
pr_ch_x, |
|
|
double & |
pr_ch_y, |
|
|
double & |
pr_ch_a, |
|
|
double |
dt |
|
) |
| |
|
private |
void scan_tools::LaserScanMatcher::imuCallback |
( |
const sensor_msgs::Imu::ConstPtr & |
imu_msg | ) |
|
|
private |
void scan_tools::LaserScanMatcher::initParams |
( |
| ) |
|
|
private |
void scan_tools::LaserScanMatcher::laserScanToLDP |
( |
const sensor_msgs::LaserScan::ConstPtr & |
scan_msg, |
|
|
LDP & |
ldp |
|
) |
| |
|
private |
bool scan_tools::LaserScanMatcher::newKeyframeNeeded |
( |
const tf::Transform & |
d | ) |
|
|
private |
void scan_tools::LaserScanMatcher::odomCallback |
( |
const nav_msgs::Odometry::ConstPtr & |
odom_msg | ) |
|
|
private |
void scan_tools::LaserScanMatcher::PointCloudToLDP |
( |
const PointCloudT::ConstPtr & |
cloud, |
|
|
LDP & |
ldp |
|
) |
| |
|
private |
void scan_tools::LaserScanMatcher::processScan |
( |
LDP & |
curr_ldp_scan, |
|
|
const ros::Time & |
time |
|
) |
| |
|
private |
void scan_tools::LaserScanMatcher::scanCallback |
( |
const sensor_msgs::LaserScan::ConstPtr & |
scan_msg | ) |
|
|
private |
void scan_tools::LaserScanMatcher::velCallback |
( |
const geometry_msgs::Twist::ConstPtr & |
twist_msg | ) |
|
|
private |
void scan_tools::LaserScanMatcher::velStmpCallback |
( |
const geometry_msgs::TwistStamped::ConstPtr & |
twist_msg | ) |
|
|
private |
std::vector<double> scan_tools::LaserScanMatcher::a_cos_ |
|
private |
std::vector<double> scan_tools::LaserScanMatcher::a_sin_ |
|
private |
std::string scan_tools::LaserScanMatcher::base_frame_ |
|
private |
double scan_tools::LaserScanMatcher::cloud_range_max_ |
|
private |
double scan_tools::LaserScanMatcher::cloud_range_min_ |
|
private |
double scan_tools::LaserScanMatcher::cloud_res_ |
|
private |
std::string scan_tools::LaserScanMatcher::fixed_frame_ |
|
private |
bool scan_tools::LaserScanMatcher::initialized_ |
|
private |
sm_params scan_tools::LaserScanMatcher::input_ |
|
private |
double scan_tools::LaserScanMatcher::kf_dist_angular_ |
|
private |
double scan_tools::LaserScanMatcher::kf_dist_linear_ |
|
private |
double scan_tools::LaserScanMatcher::kf_dist_linear_sq_ |
|
private |
ros::Time scan_tools::LaserScanMatcher::last_icp_time_ |
|
private |
sensor_msgs::Imu scan_tools::LaserScanMatcher::last_used_imu_msg_ |
|
private |
sensor_msgs::Imu scan_tools::LaserScanMatcher::latest_imu_msg_ |
|
private |
geometry_msgs::Twist scan_tools::LaserScanMatcher::latest_vel_msg_ |
|
private |
boost::mutex scan_tools::LaserScanMatcher::mutex_ |
|
private |
std::vector<double> scan_tools::LaserScanMatcher::orientation_covariance_ |
|
private |
sm_result scan_tools::LaserScanMatcher::output_ |
|
private |
ros::Publisher scan_tools::LaserScanMatcher::pose_with_covariance_publisher_ |
|
private |
ros::Publisher scan_tools::LaserScanMatcher::pose_with_covariance_stamped_publisher_ |
|
private |
std::vector<double> scan_tools::LaserScanMatcher::position_covariance_ |
|
private |
LDP scan_tools::LaserScanMatcher::prev_ldp_scan_ |
|
private |
bool scan_tools::LaserScanMatcher::publish_pose_ |
|
private |
bool scan_tools::LaserScanMatcher::publish_pose_stamped_ |
|
private |
bool scan_tools::LaserScanMatcher::publish_pose_with_covariance_ |
|
private |
bool scan_tools::LaserScanMatcher::publish_pose_with_covariance_stamped_ |
|
private |
bool scan_tools::LaserScanMatcher::publish_tf_ |
|
private |
bool scan_tools::LaserScanMatcher::received_imu_ |
|
private |
bool scan_tools::LaserScanMatcher::received_odom_ |
|
private |
bool scan_tools::LaserScanMatcher::received_vel_ |
|
private |
bool scan_tools::LaserScanMatcher::stamped_vel_ |
|
private |
bool scan_tools::LaserScanMatcher::use_cloud_input_ |
|
private |
bool scan_tools::LaserScanMatcher::use_imu_ |
|
private |
bool scan_tools::LaserScanMatcher::use_odom_ |
|
private |
bool scan_tools::LaserScanMatcher::use_vel_ |
|
private |
The documentation for this class was generated from the following files: