#include <laser_scan_matcher.h>
Public Member Functions | |
LaserScanMatcher (ros::NodeHandle nh, ros::NodeHandle nh_private) | |
~LaserScanMatcher () | |
Private Types | |
typedef pcl::PointCloud< PointT > | PointCloudT |
typedef pcl::PointXYZ | PointT |
Private Member Functions | |
void | cloudCallback (const PointCloudT::ConstPtr &cloud) |
void | createCache (const sensor_msgs::LaserScan::ConstPtr &scan_msg) |
void | createTfFromXYTheta (double x, double y, double theta, tf::Transform &t) |
bool | getBaseToLaserTf (const std::string &frame_id) |
void | getPrediction (double &pr_ch_x, double &pr_ch_y, double &pr_ch_a, double dt) |
void | imuCallback (const sensor_msgs::Imu::ConstPtr &imu_msg) |
void | initParams () |
void | laserScanToLDP (const sensor_msgs::LaserScan::ConstPtr &scan_msg, LDP &ldp) |
bool | newKeyframeNeeded (const tf::Transform &d) |
void | odomCallback (const nav_msgs::Odometry::ConstPtr &odom_msg) |
void | PointCloudToLDP (const PointCloudT::ConstPtr &cloud, LDP &ldp) |
void | processScan (LDP &curr_ldp_scan, const ros::Time &time) |
void | scanCallback (const sensor_msgs::LaserScan::ConstPtr &scan_msg) |
void | velCallback (const geometry_msgs::TwistStamped::ConstPtr &twist_msg) |
Private Attributes | |
std::vector< double > | a_cos_ |
std::vector< double > | a_sin_ |
std::string | base_frame_ |
tf::Transform | base_to_laser_ |
double | cloud_range_max_ |
double | cloud_range_min_ |
double | cloud_res_ |
ros::Subscriber | cloud_subscriber_ |
tf::Transform | f2b_ |
tf::Transform | f2b_kf_ |
std::string | fixed_frame_ |
ros::Subscriber | imu_subscriber_ |
bool | initialized_ |
sm_params | input_ |
double | kf_dist_angular_ |
double | kf_dist_linear_ |
double | kf_dist_linear_sq_ |
tf::Transform | laser_to_base_ |
ros::Time | last_icp_time_ |
sensor_msgs::Imu | last_used_imu_msg_ |
nav_msgs::Odometry | last_used_odom_msg_ |
sensor_msgs::Imu | latest_imu_msg_ |
nav_msgs::Odometry | latest_odom_msg_ |
geometry_msgs::TwistStamped | latest_vel_msg_ |
boost::mutex | mutex_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | nh_private_ |
ros::Subscriber | odom_subscriber_ |
sm_result | output_ |
ros::Publisher | pose_publisher_ |
ros::Publisher | pose_stamped_publisher_ |
LDP | prev_ldp_scan_ |
bool | publish_pose_ |
bool | publish_pose_stamped_ |
bool | publish_tf_ |
bool | received_imu_ |
bool | received_odom_ |
bool | received_vel_ |
ros::Subscriber | scan_subscriber_ |
tf::TransformBroadcaster | tf_broadcaster_ |
tf::TransformListener | tf_listener_ |
bool | use_cloud_input_ |
bool | use_imu_ |
bool | use_odom_ |
bool | use_vel_ |
ros::Subscriber | vel_subscriber_ |
Definition at line 63 of file laser_scan_matcher.h.
typedef pcl::PointCloud<PointT> scan_tools::LaserScanMatcher::PointCloudT [private] |
Definition at line 73 of file laser_scan_matcher.h.
typedef pcl::PointXYZ scan_tools::LaserScanMatcher::PointT [private] |
Definition at line 72 of file laser_scan_matcher.h.
scan_tools::LaserScanMatcher::LaserScanMatcher | ( | ros::NodeHandle | nh, |
ros::NodeHandle | nh_private | ||
) |
Definition at line 43 of file laser_scan_matcher.cpp.
Definition at line 109 of file laser_scan_matcher.cpp.
void scan_tools::LaserScanMatcher::cloudCallback | ( | const PointCloudT::ConstPtr & | cloud | ) | [private] |
Definition at line 324 of file laser_scan_matcher.cpp.
void scan_tools::LaserScanMatcher::createCache | ( | const sensor_msgs::LaserScan::ConstPtr & | scan_msg | ) | [private] |
Definition at line 620 of file laser_scan_matcher.cpp.
void scan_tools::LaserScanMatcher::createTfFromXYTheta | ( | double | x, |
double | y, | ||
double | theta, | ||
tf::Transform & | t | ||
) | [private] |
Definition at line 713 of file laser_scan_matcher.cpp.
bool scan_tools::LaserScanMatcher::getBaseToLaserTf | ( | const std::string & | frame_id | ) | [private] |
Definition at line 636 of file laser_scan_matcher.cpp.
void scan_tools::LaserScanMatcher::getPrediction | ( | double & | pr_ch_x, |
double & | pr_ch_y, | ||
double & | pr_ch_a, | ||
double | dt | ||
) | [private] |
Definition at line 661 of file laser_scan_matcher.cpp.
void scan_tools::LaserScanMatcher::imuCallback | ( | const sensor_msgs::Imu::ConstPtr & | imu_msg | ) | [private] |
Definition at line 294 of file laser_scan_matcher.cpp.
void scan_tools::LaserScanMatcher::initParams | ( | ) | [private] |
Definition at line 114 of file laser_scan_matcher.cpp.
void scan_tools::LaserScanMatcher::laserScanToLDP | ( | const sensor_msgs::LaserScan::ConstPtr & | scan_msg, |
LDP & | ldp | ||
) | [private] |
Definition at line 578 of file laser_scan_matcher.cpp.
bool scan_tools::LaserScanMatcher::newKeyframeNeeded | ( | const tf::Transform & | d | ) | [private] |
Definition at line 498 of file laser_scan_matcher.cpp.
void scan_tools::LaserScanMatcher::odomCallback | ( | const nav_msgs::Odometry::ConstPtr & | odom_msg | ) | [private] |
Definition at line 305 of file laser_scan_matcher.cpp.
void scan_tools::LaserScanMatcher::PointCloudToLDP | ( | const PointCloudT::ConstPtr & | cloud, |
LDP & | ldp | ||
) | [private] |
Definition at line 509 of file laser_scan_matcher.cpp.
void scan_tools::LaserScanMatcher::processScan | ( | LDP & | curr_ldp_scan, |
const ros::Time & | time | ||
) | [private] |
Definition at line 372 of file laser_scan_matcher.cpp.
void scan_tools::LaserScanMatcher::scanCallback | ( | const sensor_msgs::LaserScan::ConstPtr & | scan_msg | ) | [private] |
Definition at line 347 of file laser_scan_matcher.cpp.
void scan_tools::LaserScanMatcher::velCallback | ( | const geometry_msgs::TwistStamped::ConstPtr & | twist_msg | ) | [private] |
Definition at line 316 of file laser_scan_matcher.cpp.
std::vector<double> scan_tools::LaserScanMatcher::a_cos_ [private] |
Definition at line 143 of file laser_scan_matcher.h.
std::vector<double> scan_tools::LaserScanMatcher::a_sin_ [private] |
Definition at line 144 of file laser_scan_matcher.h.
std::string scan_tools::LaserScanMatcher::base_frame_ [private] |
Definition at line 97 of file laser_scan_matcher.h.
Definition at line 89 of file laser_scan_matcher.h.
double scan_tools::LaserScanMatcher::cloud_range_max_ [private] |
Definition at line 100 of file laser_scan_matcher.h.
double scan_tools::LaserScanMatcher::cloud_range_min_ [private] |
Definition at line 99 of file laser_scan_matcher.h.
double scan_tools::LaserScanMatcher::cloud_res_ [private] |
Definition at line 101 of file laser_scan_matcher.h.
Definition at line 81 of file laser_scan_matcher.h.
Definition at line 131 of file laser_scan_matcher.h.
Definition at line 132 of file laser_scan_matcher.h.
std::string scan_tools::LaserScanMatcher::fixed_frame_ [private] |
Definition at line 98 of file laser_scan_matcher.h.
Definition at line 83 of file laser_scan_matcher.h.
bool scan_tools::LaserScanMatcher::initialized_ [private] |
Definition at line 126 of file laser_scan_matcher.h.
sm_params scan_tools::LaserScanMatcher::input_ [private] |
Definition at line 146 of file laser_scan_matcher.h.
double scan_tools::LaserScanMatcher::kf_dist_angular_ [private] |
Definition at line 110 of file laser_scan_matcher.h.
double scan_tools::LaserScanMatcher::kf_dist_linear_ [private] |
Definition at line 108 of file laser_scan_matcher.h.
double scan_tools::LaserScanMatcher::kf_dist_linear_sq_ [private] |
Definition at line 109 of file laser_scan_matcher.h.
Definition at line 90 of file laser_scan_matcher.h.
Definition at line 134 of file laser_scan_matcher.h.
sensor_msgs::Imu scan_tools::LaserScanMatcher::last_used_imu_msg_ [private] |
Definition at line 137 of file laser_scan_matcher.h.
nav_msgs::Odometry scan_tools::LaserScanMatcher::last_used_odom_msg_ [private] |
Definition at line 139 of file laser_scan_matcher.h.
sensor_msgs::Imu scan_tools::LaserScanMatcher::latest_imu_msg_ [private] |
Definition at line 136 of file laser_scan_matcher.h.
nav_msgs::Odometry scan_tools::LaserScanMatcher::latest_odom_msg_ [private] |
Definition at line 138 of file laser_scan_matcher.h.
geometry_msgs::TwistStamped scan_tools::LaserScanMatcher::latest_vel_msg_ [private] |
Definition at line 141 of file laser_scan_matcher.h.
boost::mutex scan_tools::LaserScanMatcher::mutex_ [private] |
Definition at line 124 of file laser_scan_matcher.h.
Definition at line 77 of file laser_scan_matcher.h.
Definition at line 78 of file laser_scan_matcher.h.
Definition at line 82 of file laser_scan_matcher.h.
sm_result scan_tools::LaserScanMatcher::output_ [private] |
Definition at line 147 of file laser_scan_matcher.h.
Definition at line 92 of file laser_scan_matcher.h.
Definition at line 93 of file laser_scan_matcher.h.
LDP scan_tools::LaserScanMatcher::prev_ldp_scan_ [private] |
Definition at line 148 of file laser_scan_matcher.h.
bool scan_tools::LaserScanMatcher::publish_pose_ [private] |
Definition at line 103 of file laser_scan_matcher.h.
bool scan_tools::LaserScanMatcher::publish_pose_stamped_ [private] |
Definition at line 104 of file laser_scan_matcher.h.
bool scan_tools::LaserScanMatcher::publish_tf_ [private] |
Definition at line 102 of file laser_scan_matcher.h.
bool scan_tools::LaserScanMatcher::received_imu_ [private] |
Definition at line 127 of file laser_scan_matcher.h.
bool scan_tools::LaserScanMatcher::received_odom_ [private] |
Definition at line 128 of file laser_scan_matcher.h.
bool scan_tools::LaserScanMatcher::received_vel_ [private] |
Definition at line 129 of file laser_scan_matcher.h.
Definition at line 80 of file laser_scan_matcher.h.
Definition at line 87 of file laser_scan_matcher.h.
Definition at line 86 of file laser_scan_matcher.h.
bool scan_tools::LaserScanMatcher::use_cloud_input_ [private] |
Definition at line 106 of file laser_scan_matcher.h.
bool scan_tools::LaserScanMatcher::use_imu_ [private] |
Definition at line 118 of file laser_scan_matcher.h.
bool scan_tools::LaserScanMatcher::use_odom_ [private] |
Definition at line 119 of file laser_scan_matcher.h.
bool scan_tools::LaserScanMatcher::use_vel_ [private] |
Definition at line 120 of file laser_scan_matcher.h.
Definition at line 84 of file laser_scan_matcher.h.