scan_tools::LaserScanMatcher Class Reference

#include <laser_scan_matcher.h>

List of all members.

Public Member Functions

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

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)
double getYawFromQuaternion (const tf::Quaternion &quaternion)
double getYawFromQuaternion (const geometry_msgs::Quaternion &quaternion)
void imuCallback (const sensor_msgs::ImuPtr &imu_msg)
void initParams ()
void laserScanToLDP (const sensor_msgs::LaserScan::ConstPtr &scan_msg, LDP &ldp)
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)

Private Attributes

std::vector< double > a_cos_
std::vector< double > a_sin_
double alpha_
std::string base_frame_
tf::Transform base_to_laser_
double beta_
double cloud_range_max_
double cloud_range_min_
ros::Subscriber cloud_subscriber_
std::string fixed_frame_
ros::Subscriber imu_subscriber_
bool initialized_
sm_params input_
tf::Transform laser_to_base_
ros::Time last_icp_time_
double last_imu_yaw_
nav_msgs::Odometry last_odom_
double latest_imu_yaw_
nav_msgs::Odometry latest_odom_
boost::mutex mutex_
ros::NodeHandle nh_
ros::NodeHandle nh_private_
ros::Subscriber odom_subscriber_
sm_result output_
ros::Publisher pose_publisher_
LDP prev_ldp_scan_
bool publish_pose_
bool publish_tf_
bool received_imu_
bool received_odom_
ros::Subscriber scan_subscriber_
ros::Publisher test_pub_
tf::TransformBroadcaster tf_broadcaster_
tf::TransformListener tf_listener_
bool use_alpha_beta_
bool use_cloud_input_
bool use_imu_
bool use_odom_
double v_a_
double v_x_
double v_y_
ros::Publisher vel_publisher_
tf::Transform w2b_

Detailed Description

Definition at line 68 of file laser_scan_matcher.h.


Constructor & Destructor Documentation

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

Definition at line 43 of file laser_scan_matcher.cpp.

scan_tools::LaserScanMatcher::~LaserScanMatcher (  ) 

Definition at line 103 of file laser_scan_matcher.cpp.


Member Function Documentation

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

Definition at line 301 of file laser_scan_matcher.cpp.

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

Definition at line 590 of file laser_scan_matcher.cpp.

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

Definition at line 690 of file laser_scan_matcher.cpp.

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

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

double scan_tools::LaserScanMatcher::getYawFromQuaternion ( const tf::Quaternion &  quaternion  )  [private]

Definition at line 673 of file laser_scan_matcher.cpp.

double scan_tools::LaserScanMatcher::getYawFromQuaternion ( const geometry_msgs::Quaternion &  quaternion  )  [private]

Definition at line 682 of file laser_scan_matcher.cpp.

void scan_tools::LaserScanMatcher::imuCallback ( const sensor_msgs::ImuPtr &  imu_msg  )  [private]

Definition at line 279 of file laser_scan_matcher.cpp.

void scan_tools::LaserScanMatcher::initParams (  )  [private]

Definition at line 108 of file laser_scan_matcher.cpp.

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

Definition at line 548 of file laser_scan_matcher.cpp.

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

Definition at line 290 of file laser_scan_matcher.cpp.

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

Definition at line 500 of file laser_scan_matcher.cpp.

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

Definition at line 353 of file laser_scan_matcher.cpp.

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

Definition at line 326 of file laser_scan_matcher.cpp.


Member Data Documentation

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

Definition at line 139 of file laser_scan_matcher.h.

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

Definition at line 140 of file laser_scan_matcher.h.

Definition at line 113 of file laser_scan_matcher.h.

Definition at line 94 of file laser_scan_matcher.h.

Definition at line 85 of file laser_scan_matcher.h.

Definition at line 114 of file laser_scan_matcher.h.

Definition at line 97 of file laser_scan_matcher.h.

Definition at line 96 of file laser_scan_matcher.h.

Definition at line 78 of file laser_scan_matcher.h.

Definition at line 95 of file laser_scan_matcher.h.

Definition at line 80 of file laser_scan_matcher.h.

Definition at line 118 of file laser_scan_matcher.h.

Definition at line 142 of file laser_scan_matcher.h.

Definition at line 86 of file laser_scan_matcher.h.

Definition at line 131 of file laser_scan_matcher.h.

Definition at line 134 of file laser_scan_matcher.h.

nav_msgs::Odometry scan_tools::LaserScanMatcher::last_odom_ [private]

Definition at line 137 of file laser_scan_matcher.h.

Definition at line 133 of file laser_scan_matcher.h.

nav_msgs::Odometry scan_tools::LaserScanMatcher::latest_odom_ [private]

Definition at line 136 of file laser_scan_matcher.h.

boost::mutex scan_tools::LaserScanMatcher::mutex_ [private]

Definition at line 123 of file laser_scan_matcher.h.

ros::NodeHandle scan_tools::LaserScanMatcher::nh_ [private]

Definition at line 74 of file laser_scan_matcher.h.

ros::NodeHandle scan_tools::LaserScanMatcher::nh_private_ [private]

Definition at line 75 of file laser_scan_matcher.h.

Definition at line 79 of file laser_scan_matcher.h.

Definition at line 143 of file laser_scan_matcher.h.

Definition at line 89 of file laser_scan_matcher.h.

Definition at line 144 of file laser_scan_matcher.h.

Definition at line 99 of file laser_scan_matcher.h.

Definition at line 98 of file laser_scan_matcher.h.

Definition at line 120 of file laser_scan_matcher.h.

Definition at line 121 of file laser_scan_matcher.h.

Definition at line 77 of file laser_scan_matcher.h.

ros::Publisher scan_tools::LaserScanMatcher::test_pub_ [private]

Definition at line 88 of file laser_scan_matcher.h.

tf::TransformBroadcaster scan_tools::LaserScanMatcher::tf_broadcaster_ [private]

Definition at line 83 of file laser_scan_matcher.h.

tf::TransformListener scan_tools::LaserScanMatcher::tf_listener_ [private]

Definition at line 82 of file laser_scan_matcher.h.

Definition at line 111 of file laser_scan_matcher.h.

Definition at line 101 of file laser_scan_matcher.h.

Definition at line 109 of file laser_scan_matcher.h.

Definition at line 110 of file laser_scan_matcher.h.

Definition at line 129 of file laser_scan_matcher.h.

Definition at line 127 of file laser_scan_matcher.h.

Definition at line 128 of file laser_scan_matcher.h.

Definition at line 90 of file laser_scan_matcher.h.

tf::Transform scan_tools::LaserScanMatcher::w2b_ [private]

Definition at line 125 of file laser_scan_matcher.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs


laser_scan_matcher
Author(s): Ivan Dryanovski, William Morris
autogenerated on Fri Jan 11 09:12:54 2013