Public Member Functions | Private Types | 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 Types

typedef pcl::PointCloud< PointTPointCloudT
 
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 getBaseLaserTransform (const std::string &frame_id)
 
Eigen::Matrix2f getLaserRotation (const tf::Transform &odom_pose) const
 
tf::Transform getPrediction (const ros::Time &stamp)
 
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::Twist::ConstPtr &twist_msg)
 
void velStmpCallback (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_from_laser_
 
double cloud_range_max_
 
double cloud_range_min_
 
double cloud_res_
 
ros::Subscriber cloud_subscriber_
 
std::string fixed_frame_
 
ros::Subscriber imu_subscriber_
 
bool initialized_
 
sm_params input_
 
tf::Transform keyframe_base_in_fixed_
 
double kf_dist_angular_
 
double kf_dist_linear_
 
double kf_dist_linear_sq_
 
tf::Transform laser_from_base_
 
tf::Transform last_base_in_fixed_
 
ros::Time last_icp_time_
 
tf::Quaternion last_used_imu_orientation_
 
tf::Transform last_used_odom_pose_
 
sensor_msgs::Imu latest_imu_msg_
 
nav_msgs::Odometry latest_odom_msg_
 
geometry_msgs::Twist latest_vel_msg_
 
boost::mutex mutex_
 
ros::NodeHandle nh_
 
ros::NodeHandle nh_private_
 
ros::Subscriber odom_subscriber_
 
std::vector< double > orientation_covariance_
 
sm_result output_
 
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_
 
LDP prev_ldp_scan_
 
bool publish_pose_
 
bool publish_pose_stamped_
 
bool publish_pose_with_covariance_
 
bool publish_pose_with_covariance_stamped_
 
bool publish_tf_
 
bool received_imu_
 
bool received_odom_
 
bool received_vel_
 
ros::Subscriber scan_subscriber_
 
bool stamped_vel_
 
tf::TransformBroadcaster tf_broadcaster_
 
tf::TransformListener tf_listener_
 
double tf_timeout_
 
bool use_cloud_input_
 
bool use_imu_
 
bool use_odom_
 
bool use_tf_
 
bool use_vel_
 
ros::Subscriber vel_subscriber_
 

Detailed Description

Definition at line 65 of file laser_scan_matcher.h.

Member Typedef Documentation

◆ PointCloudT

Definition at line 75 of file laser_scan_matcher.h.

◆ PointT

typedef pcl::PointXYZ scan_tools::LaserScanMatcher::PointT
private

Definition at line 74 of file laser_scan_matcher.h.

Constructor & Destructor Documentation

◆ LaserScanMatcher()

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

Definition at line 46 of file laser_scan_matcher.cpp.

◆ ~LaserScanMatcher()

scan_tools::LaserScanMatcher::~LaserScanMatcher ( )

Definition at line 134 of file laser_scan_matcher.cpp.

Member Function Documentation

◆ cloudCallback()

void scan_tools::LaserScanMatcher::cloudCallback ( const PointCloudT::ConstPtr &  cloud)
private

Definition at line 382 of file laser_scan_matcher.cpp.

◆ createCache()

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

Definition at line 752 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 852 of file laser_scan_matcher.cpp.

◆ getBaseLaserTransform()

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

Cache the static transform between the base and laser.

Parameters
[in]frame_idThe laser frame.
Returns
True if the transform was found, false otherwise.

Definition at line 768 of file laser_scan_matcher.cpp.

◆ getLaserRotation()

Eigen::Matrix2f scan_tools::LaserScanMatcher::getLaserRotation ( const tf::Transform odom_pose) const
private

Definition at line 861 of file laser_scan_matcher.cpp.

◆ getPrediction()

tf::Transform scan_tools::LaserScanMatcher::getPrediction ( const ros::Time stamp)
private

Definition at line 788 of file laser_scan_matcher.cpp.

◆ imuCallback()

void scan_tools::LaserScanMatcher::imuCallback ( const sensor_msgs::Imu::ConstPtr &  imu_msg)
private

Definition at line 344 of file laser_scan_matcher.cpp.

◆ initParams()

void scan_tools::LaserScanMatcher::initParams ( )
private

Definition at line 139 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 710 of file laser_scan_matcher.cpp.

◆ newKeyframeNeeded()

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

Definition at line 630 of file laser_scan_matcher.cpp.

◆ odomCallback()

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

Definition at line 355 of file laser_scan_matcher.cpp.

◆ PointCloudToLDP()

void scan_tools::LaserScanMatcher::PointCloudToLDP ( const PointCloudT::ConstPtr &  cloud,
LDP ldp 
)
private

Definition at line 641 of file laser_scan_matcher.cpp.

◆ processScan()

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

Definition at line 432 of file laser_scan_matcher.cpp.

◆ scanCallback()

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

Definition at line 407 of file laser_scan_matcher.cpp.

◆ velCallback()

void scan_tools::LaserScanMatcher::velCallback ( const geometry_msgs::Twist::ConstPtr &  twist_msg)
private

Definition at line 366 of file laser_scan_matcher.cpp.

◆ velStmpCallback()

void scan_tools::LaserScanMatcher::velStmpCallback ( const geometry_msgs::TwistStamped::ConstPtr &  twist_msg)
private

Definition at line 374 of file laser_scan_matcher.cpp.

Member Data Documentation

◆ a_cos_

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

Definition at line 155 of file laser_scan_matcher.h.

◆ a_sin_

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

Definition at line 156 of file laser_scan_matcher.h.

◆ base_frame_

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

Definition at line 101 of file laser_scan_matcher.h.

◆ base_from_laser_

tf::Transform scan_tools::LaserScanMatcher::base_from_laser_
private

Definition at line 91 of file laser_scan_matcher.h.

◆ cloud_range_max_

double scan_tools::LaserScanMatcher::cloud_range_max_
private

Definition at line 104 of file laser_scan_matcher.h.

◆ cloud_range_min_

double scan_tools::LaserScanMatcher::cloud_range_min_
private

Definition at line 103 of file laser_scan_matcher.h.

◆ cloud_res_

double scan_tools::LaserScanMatcher::cloud_res_
private

Definition at line 105 of file laser_scan_matcher.h.

◆ cloud_subscriber_

ros::Subscriber scan_tools::LaserScanMatcher::cloud_subscriber_
private

Definition at line 83 of file laser_scan_matcher.h.

◆ fixed_frame_

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

Definition at line 102 of file laser_scan_matcher.h.

◆ imu_subscriber_

ros::Subscriber scan_tools::LaserScanMatcher::imu_subscriber_
private

Definition at line 85 of file laser_scan_matcher.h.

◆ initialized_

bool scan_tools::LaserScanMatcher::initialized_
private

Definition at line 138 of file laser_scan_matcher.h.

◆ input_

sm_params scan_tools::LaserScanMatcher::input_
private

Definition at line 158 of file laser_scan_matcher.h.

◆ keyframe_base_in_fixed_

tf::Transform scan_tools::LaserScanMatcher::keyframe_base_in_fixed_
private

Definition at line 144 of file laser_scan_matcher.h.

◆ kf_dist_angular_

double scan_tools::LaserScanMatcher::kf_dist_angular_
private

Definition at line 118 of file laser_scan_matcher.h.

◆ kf_dist_linear_

double scan_tools::LaserScanMatcher::kf_dist_linear_
private

Definition at line 116 of file laser_scan_matcher.h.

◆ kf_dist_linear_sq_

double scan_tools::LaserScanMatcher::kf_dist_linear_sq_
private

Definition at line 117 of file laser_scan_matcher.h.

◆ laser_from_base_

tf::Transform scan_tools::LaserScanMatcher::laser_from_base_
private

Definition at line 92 of file laser_scan_matcher.h.

◆ last_base_in_fixed_

tf::Transform scan_tools::LaserScanMatcher::last_base_in_fixed_
private

Definition at line 143 of file laser_scan_matcher.h.

◆ last_icp_time_

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

Definition at line 146 of file laser_scan_matcher.h.

◆ last_used_imu_orientation_

tf::Quaternion scan_tools::LaserScanMatcher::last_used_imu_orientation_
private

Definition at line 149 of file laser_scan_matcher.h.

◆ last_used_odom_pose_

tf::Transform scan_tools::LaserScanMatcher::last_used_odom_pose_
private

Definition at line 151 of file laser_scan_matcher.h.

◆ latest_imu_msg_

sensor_msgs::Imu scan_tools::LaserScanMatcher::latest_imu_msg_
private

Definition at line 148 of file laser_scan_matcher.h.

◆ latest_odom_msg_

nav_msgs::Odometry scan_tools::LaserScanMatcher::latest_odom_msg_
private

Definition at line 150 of file laser_scan_matcher.h.

◆ latest_vel_msg_

geometry_msgs::Twist scan_tools::LaserScanMatcher::latest_vel_msg_
private

Definition at line 153 of file laser_scan_matcher.h.

◆ mutex_

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

Definition at line 136 of file laser_scan_matcher.h.

◆ nh_

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

Definition at line 79 of file laser_scan_matcher.h.

◆ nh_private_

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

Definition at line 80 of file laser_scan_matcher.h.

◆ odom_subscriber_

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

Definition at line 84 of file laser_scan_matcher.h.

◆ orientation_covariance_

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

Definition at line 112 of file laser_scan_matcher.h.

◆ output_

sm_result scan_tools::LaserScanMatcher::output_
private

Definition at line 159 of file laser_scan_matcher.h.

◆ pose_publisher_

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

Definition at line 94 of file laser_scan_matcher.h.

◆ pose_stamped_publisher_

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

Definition at line 95 of file laser_scan_matcher.h.

◆ pose_with_covariance_publisher_

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

Definition at line 96 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 97 of file laser_scan_matcher.h.

◆ position_covariance_

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

Definition at line 111 of file laser_scan_matcher.h.

◆ prev_ldp_scan_

LDP scan_tools::LaserScanMatcher::prev_ldp_scan_
private

Definition at line 160 of file laser_scan_matcher.h.

◆ publish_pose_

bool scan_tools::LaserScanMatcher::publish_pose_
private

Definition at line 107 of file laser_scan_matcher.h.

◆ publish_pose_stamped_

bool scan_tools::LaserScanMatcher::publish_pose_stamped_
private

Definition at line 109 of file laser_scan_matcher.h.

◆ publish_pose_with_covariance_

bool scan_tools::LaserScanMatcher::publish_pose_with_covariance_
private

Definition at line 108 of file laser_scan_matcher.h.

◆ publish_pose_with_covariance_stamped_

bool scan_tools::LaserScanMatcher::publish_pose_with_covariance_stamped_
private

Definition at line 110 of file laser_scan_matcher.h.

◆ publish_tf_

bool scan_tools::LaserScanMatcher::publish_tf_
private

Definition at line 106 of file laser_scan_matcher.h.

◆ received_imu_

bool scan_tools::LaserScanMatcher::received_imu_
private

Definition at line 139 of file laser_scan_matcher.h.

◆ received_odom_

bool scan_tools::LaserScanMatcher::received_odom_
private

Definition at line 140 of file laser_scan_matcher.h.

◆ received_vel_

bool scan_tools::LaserScanMatcher::received_vel_
private

Definition at line 141 of file laser_scan_matcher.h.

◆ scan_subscriber_

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

Definition at line 82 of file laser_scan_matcher.h.

◆ stamped_vel_

bool scan_tools::LaserScanMatcher::stamped_vel_
private

Definition at line 132 of file laser_scan_matcher.h.

◆ tf_broadcaster_

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

Definition at line 89 of file laser_scan_matcher.h.

◆ tf_listener_

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

Definition at line 88 of file laser_scan_matcher.h.

◆ tf_timeout_

double scan_tools::LaserScanMatcher::tf_timeout_
private

Definition at line 130 of file laser_scan_matcher.h.

◆ use_cloud_input_

bool scan_tools::LaserScanMatcher::use_cloud_input_
private

Definition at line 114 of file laser_scan_matcher.h.

◆ use_imu_

bool scan_tools::LaserScanMatcher::use_imu_
private

Definition at line 127 of file laser_scan_matcher.h.

◆ use_odom_

bool scan_tools::LaserScanMatcher::use_odom_
private

Definition at line 128 of file laser_scan_matcher.h.

◆ use_tf_

bool scan_tools::LaserScanMatcher::use_tf_
private

Definition at line 129 of file laser_scan_matcher.h.

◆ use_vel_

bool scan_tools::LaserScanMatcher::use_vel_
private

Definition at line 131 of file laser_scan_matcher.h.

◆ vel_subscriber_

ros::Subscriber scan_tools::LaserScanMatcher::vel_subscriber_
private

Definition at line 86 of file laser_scan_matcher.h.


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


laser_scan_matcher
Author(s): Ivan Dryanovski , William Morris, Andrea Censi
autogenerated on Thu Oct 19 2023 02:48:35