Public Member Functions | Protected Attributes
NDTFuserNode Class Reference

List of all members.

Public Member Functions

void gt_callback (const nav_msgs::Odometry::ConstPtr &msg_in)
void laserCallback (const sensor_msgs::LaserScan::ConstPtr &msg_in)
void laserOdomCallback (const sensor_msgs::LaserScan::ConstPtr &msg_in, const nav_msgs::Odometry::ConstPtr &odo_in)
 NDTFuserNode (ros::NodeHandle param_nh)
void points2Callback (const sensor_msgs::PointCloud2::ConstPtr &msg_in)
void points2OdomCallback (const sensor_msgs::PointCloud2::ConstPtr &msg_in, const nav_msgs::Odometry::ConstPtr &odo_in)
void processFrame (pcl::PointCloud< pcl::PointXYZ > &cloud, Eigen::Affine3d Tmotion)
bool save_map_callback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 ~NDTFuserNode ()

Protected Attributes

bool beHMT
lslgeneric::NDTFuserHMT
< pcl::PointXYZ > * 
fuser
std::string fuser_frame
ros::Subscriber gt_sub
std::string gt_topic
std::string init_pose_frame
bool initPoseFromGT
bool initPoseFromTF
bool initPoseSet
message_filters::Subscriber
< sensor_msgs::LaserScan > * 
laser_sub_
std::string laser_topic
Eigen::Affine3d last_odom
boost::mutex m
std::string map_dir
std::string map_name
bool match2D
bool matchLaser
boost::mutex message_m
double min_laser_range_
unsigned int nb_added_clouds_
ros::NodeHandle nh_
message_filters::Subscriber
< nav_msgs::Odometry > * 
odom_sub_
std::string odometry_topic
ros::Publisher output_pub_
bool plotGTTrack
message_filters::Subscriber
< sensor_msgs::PointCloud2 > * 
points2_sub_
std::string points_topic
Eigen::Affine3d pose_
double pose_init_p
double pose_init_r
double pose_init_t
double pose_init_x
double pose_init_y
double pose_init_z
laser_geometry::LaserProjection projector_
double resolution
ros::ServiceServer save_map_
Eigen::Affine3d sensor_pose_
double sensor_pose_p
double sensor_pose_r
double sensor_pose_t
double sensor_pose_x
double sensor_pose_y
double sensor_pose_z
double sensor_range
double size_x
double size_y
double size_z
message_filters::Synchronizer
< LaserOdomSync > * 
sync_lo_
message_filters::Synchronizer
< LaserPoseSync > * 
sync_lp_
message_filters::Synchronizer
< PointsOdomSync > * 
sync_po_
message_filters::Synchronizer
< PointsPoseSync > * 
sync_pp_
Eigen::Affine3d T
tf::TransformBroadcaster tf_
Eigen::Affine3d this_odom
bool useOdometry
double varz
bool visualize
std::string world_frame

Detailed Description

Definition at line 37 of file ndt_fuser_node.cpp.


Constructor & Destructor Documentation

topic to wait for point clouds, if available

topic to wait for laser scan messages, if available

if using the HMT fuser, NDT maps are saved in this directory. a word of warning: if you run multiple times with the same directory, the old maps are loaded automatically

initial pose of the vehicle with respect to the map

pose of the sensor with respect to the vehicle odometry frame

size of the map in x/y/z. if using HMT, this is the size of the central tile

range to cutoff sensor measurements

range to cutoff sensor measurements

visualize in a local window

only mathc with 3dof

use HMT grid or simple grid.

use standard odometry messages for initial guess

topic to wait for laser scan messages, if available

if we want to compare to a ground truth topic

if we want to get the initial pose of the vehicle relative to a different frame

enable for LaserScan message input

Definition at line 80 of file ndt_fuser_node.cpp.

Definition at line 194 of file ndt_fuser_node.cpp.


Member Function Documentation

void NDTFuserNode::gt_callback ( const nav_msgs::Odometry::ConstPtr &  msg_in) [inline]

Definition at line 378 of file ndt_fuser_node.cpp.

void NDTFuserNode::laserCallback ( const sensor_msgs::LaserScan::ConstPtr &  msg_in) [inline]

Definition at line 298 of file ndt_fuser_node.cpp.

void NDTFuserNode::laserOdomCallback ( const sensor_msgs::LaserScan::ConstPtr &  msg_in,
const nav_msgs::Odometry::ConstPtr &  odo_in 
) [inline]

Definition at line 325 of file ndt_fuser_node.cpp.

void NDTFuserNode::points2Callback ( const sensor_msgs::PointCloud2::ConstPtr &  msg_in) [inline]

Definition at line 250 of file ndt_fuser_node.cpp.

void NDTFuserNode::points2OdomCallback ( const sensor_msgs::PointCloud2::ConstPtr &  msg_in,
const nav_msgs::Odometry::ConstPtr &  odo_in 
) [inline]

Definition at line 262 of file ndt_fuser_node.cpp.

void NDTFuserNode::processFrame ( pcl::PointCloud< pcl::PointXYZ > &  cloud,
Eigen::Affine3d  Tmotion 
) [inline]

Definition at line 199 of file ndt_fuser_node.cpp.

bool NDTFuserNode::save_map_callback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [inline]

Definition at line 236 of file ndt_fuser_node.cpp.


Member Data Documentation

bool NDTFuserNode::beHMT [protected]

Definition at line 61 of file ndt_fuser_node.cpp.

Definition at line 57 of file ndt_fuser_node.cpp.

std::string NDTFuserNode::fuser_frame [protected]

Definition at line 58 of file ndt_fuser_node.cpp.

Definition at line 46 of file ndt_fuser_node.cpp.

std::string NDTFuserNode::gt_topic [protected]

Definition at line 58 of file ndt_fuser_node.cpp.

std::string NDTFuserNode::init_pose_frame [protected]

Definition at line 58 of file ndt_fuser_node.cpp.

bool NDTFuserNode::initPoseFromGT [protected]

Definition at line 61 of file ndt_fuser_node.cpp.

bool NDTFuserNode::initPoseFromTF [protected]

Definition at line 61 of file ndt_fuser_node.cpp.

bool NDTFuserNode::initPoseSet [protected]

Definition at line 61 of file ndt_fuser_node.cpp.

message_filters::Subscriber<sensor_msgs::LaserScan>* NDTFuserNode::laser_sub_ [protected]

Definition at line 44 of file ndt_fuser_node.cpp.

std::string NDTFuserNode::laser_topic [protected]

Definition at line 58 of file ndt_fuser_node.cpp.

Eigen::Affine3d NDTFuserNode::last_odom [protected]

Definition at line 77 of file ndt_fuser_node.cpp.

Definition at line 56 of file ndt_fuser_node.cpp.

std::string NDTFuserNode::map_dir [protected]

Definition at line 58 of file ndt_fuser_node.cpp.

std::string NDTFuserNode::map_name [protected]

Definition at line 58 of file ndt_fuser_node.cpp.

bool NDTFuserNode::match2D [protected]

Definition at line 61 of file ndt_fuser_node.cpp.

bool NDTFuserNode::matchLaser [protected]

Definition at line 61 of file ndt_fuser_node.cpp.

Definition at line 56 of file ndt_fuser_node.cpp.

double NDTFuserNode::min_laser_range_ [protected]

Definition at line 60 of file ndt_fuser_node.cpp.

unsigned int NDTFuserNode::nb_added_clouds_ [protected]

Definition at line 53 of file ndt_fuser_node.cpp.

Definition at line 41 of file ndt_fuser_node.cpp.

message_filters::Subscriber<nav_msgs::Odometry>* NDTFuserNode::odom_sub_ [protected]

Definition at line 45 of file ndt_fuser_node.cpp.

std::string NDTFuserNode::odometry_topic [protected]

Definition at line 58 of file ndt_fuser_node.cpp.

Definition at line 50 of file ndt_fuser_node.cpp.

bool NDTFuserNode::plotGTTrack [protected]

Definition at line 61 of file ndt_fuser_node.cpp.

message_filters::Subscriber<sensor_msgs::PointCloud2>* NDTFuserNode::points2_sub_ [protected]

Definition at line 43 of file ndt_fuser_node.cpp.

std::string NDTFuserNode::points_topic [protected]

Definition at line 58 of file ndt_fuser_node.cpp.

Eigen::Affine3d NDTFuserNode::pose_ [protected]

Definition at line 51 of file ndt_fuser_node.cpp.

double NDTFuserNode::pose_init_p [protected]

Definition at line 64 of file ndt_fuser_node.cpp.

double NDTFuserNode::pose_init_r [protected]

Definition at line 64 of file ndt_fuser_node.cpp.

double NDTFuserNode::pose_init_t [protected]

Definition at line 64 of file ndt_fuser_node.cpp.

double NDTFuserNode::pose_init_x [protected]

Definition at line 64 of file ndt_fuser_node.cpp.

double NDTFuserNode::pose_init_y [protected]

Definition at line 64 of file ndt_fuser_node.cpp.

double NDTFuserNode::pose_init_z [protected]

Definition at line 64 of file ndt_fuser_node.cpp.

Definition at line 68 of file ndt_fuser_node.cpp.

double NDTFuserNode::resolution [protected]

Definition at line 60 of file ndt_fuser_node.cpp.

Definition at line 75 of file ndt_fuser_node.cpp.

Eigen::Affine3d NDTFuserNode::sensor_pose_ [protected]

Definition at line 51 of file ndt_fuser_node.cpp.

double NDTFuserNode::sensor_pose_p [protected]

Definition at line 66 of file ndt_fuser_node.cpp.

double NDTFuserNode::sensor_pose_r [protected]

Definition at line 66 of file ndt_fuser_node.cpp.

double NDTFuserNode::sensor_pose_t [protected]

Definition at line 66 of file ndt_fuser_node.cpp.

double NDTFuserNode::sensor_pose_x [protected]

Definition at line 66 of file ndt_fuser_node.cpp.

double NDTFuserNode::sensor_pose_y [protected]

Definition at line 66 of file ndt_fuser_node.cpp.

double NDTFuserNode::sensor_pose_z [protected]

Definition at line 66 of file ndt_fuser_node.cpp.

double NDTFuserNode::sensor_range [protected]

Definition at line 60 of file ndt_fuser_node.cpp.

double NDTFuserNode::size_x [protected]

Definition at line 60 of file ndt_fuser_node.cpp.

double NDTFuserNode::size_y [protected]

Definition at line 60 of file ndt_fuser_node.cpp.

double NDTFuserNode::size_z [protected]

Definition at line 60 of file ndt_fuser_node.cpp.

Definition at line 70 of file ndt_fuser_node.cpp.

Definition at line 71 of file ndt_fuser_node.cpp.

Definition at line 73 of file ndt_fuser_node.cpp.

Definition at line 74 of file ndt_fuser_node.cpp.

Eigen::Affine3d NDTFuserNode::T [protected]

Definition at line 51 of file ndt_fuser_node.cpp.

Definition at line 49 of file ndt_fuser_node.cpp.

Eigen::Affine3d NDTFuserNode::this_odom [protected]

Definition at line 77 of file ndt_fuser_node.cpp.

bool NDTFuserNode::useOdometry [protected]

Definition at line 61 of file ndt_fuser_node.cpp.

double NDTFuserNode::varz [protected]

Definition at line 54 of file ndt_fuser_node.cpp.

bool NDTFuserNode::visualize [protected]

Definition at line 61 of file ndt_fuser_node.cpp.

std::string NDTFuserNode::world_frame [protected]

Definition at line 58 of file ndt_fuser_node.cpp.


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


ndt_fuser
Author(s): Todor Stoyanov, Jari Saarinen
autogenerated on Mon Oct 6 2014 03:20:34