Public Member Functions | Private Attributes
NDTMCL3DNode Class Reference

List of all members.

Public Member Functions

void callback (const sensor_msgs::PointCloud2::ConstPtr &cloud_in, const nav_msgs::Odometry::ConstPtr &odo_in)
 NDTMCL3DNode (ros::NodeHandle param_nh)
bool sendROSOdoMessage (Eigen::Affine3d mean, ros::Time ts)
 ~NDTMCL3DNode ()

Private Attributes

bool do_visualize
bool forceSIR
bool hasInitialPose
bool hasSensorPose
Eigen::Affine3d initPoseT
bool isFirstLoad
std::string mapName
 name and the path to the map
boost::mutex mcl_m
ros::Publisher mcl_pub
 The output of MCL is published with this!
boost::mutex message_m
NDTViz ndt_viz
NDTMCL3Dndtmcl
ros::NodeHandle nh_
message_filters::Subscriber
< nav_msgs::Odometry > * 
odom_sub_
std::string odometry_topic
std::string output_map_name
int pcounter
message_filters::Subscriber
< sensor_msgs::PointCloud2 > * 
points2_sub_
std::string points_topic
double resolution
bool saveMap
 indicates if we want to save the map in a regular intervals
Eigen::Affine3d sensorPoseT
 Laser sensor offset.
double subsample_level
message_filters::Synchronizer
< PointsOdomSync > * 
sync_po_
Eigen::Affine3d Tcum
std::string tf_base_link
std::string tf_sensor_link
Eigen::Affine3d Todo
Eigen::Affine3d Todo_old
Eigen::Affine3d Told

Detailed Description

Definition at line 56 of file 3d_ndt_mcl_node.cpp.


Constructor & Destructor Documentation

Prepare Pose offsets

initial pose of the vehicle with respect to the map

pose of the sensor with respect to the vehicle odometry frame

Prepare the map

Prepare MCL object

Prepare the callbacks and message filters

topic to wait for point clouds

topic to wait for odometry messages

Definition at line 87 of file 3d_ndt_mcl_node.cpp.

Definition at line 183 of file 3d_ndt_mcl_node.cpp.


Member Function Documentation

void NDTMCL3DNode::callback ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_in,
const nav_msgs::Odometry::ConstPtr &  odo_in 
) [inline]

Set the cloud to sensor frame with respect to base

DRAW STUFF///

Definition at line 191 of file 3d_ndt_mcl_node.cpp.

bool NDTMCL3DNode::sendROSOdoMessage ( Eigen::Affine3d  mean,
ros::Time  ts 
) [inline]

Definition at line 297 of file 3d_ndt_mcl_node.cpp.


Member Data Documentation

Definition at line 73 of file 3d_ndt_mcl_node.cpp.

bool NDTMCL3DNode::forceSIR [private]

Definition at line 73 of file 3d_ndt_mcl_node.cpp.

Definition at line 71 of file 3d_ndt_mcl_node.cpp.

Definition at line 71 of file 3d_ndt_mcl_node.cpp.

Eigen::Affine3d NDTMCL3DNode::initPoseT [private]

Definition at line 69 of file 3d_ndt_mcl_node.cpp.

bool NDTMCL3DNode::isFirstLoad [private]

Definition at line 72 of file 3d_ndt_mcl_node.cpp.

std::string NDTMCL3DNode::mapName [private]

name and the path to the map

Definition at line 75 of file 3d_ndt_mcl_node.cpp.

Definition at line 61 of file 3d_ndt_mcl_node.cpp.

The output of MCL is published with this!

Definition at line 82 of file 3d_ndt_mcl_node.cpp.

Definition at line 61 of file 3d_ndt_mcl_node.cpp.

Definition at line 80 of file 3d_ndt_mcl_node.cpp.

Definition at line 60 of file 3d_ndt_mcl_node.cpp.

Definition at line 59 of file 3d_ndt_mcl_node.cpp.

message_filters::Subscriber<nav_msgs::Odometry>* NDTMCL3DNode::odom_sub_ [private]

Definition at line 64 of file 3d_ndt_mcl_node.cpp.

std::string NDTMCL3DNode::odometry_topic [private]

Definition at line 85 of file 3d_ndt_mcl_node.cpp.

std::string NDTMCL3DNode::output_map_name [private]

Definition at line 76 of file 3d_ndt_mcl_node.cpp.

int NDTMCL3DNode::pcounter [private]

Definition at line 79 of file 3d_ndt_mcl_node.cpp.

message_filters::Subscriber<sensor_msgs::PointCloud2>* NDTMCL3DNode::points2_sub_ [private]

Definition at line 63 of file 3d_ndt_mcl_node.cpp.

std::string NDTMCL3DNode::points_topic [private]

Definition at line 85 of file 3d_ndt_mcl_node.cpp.

double NDTMCL3DNode::resolution [private]

Definition at line 77 of file 3d_ndt_mcl_node.cpp.

bool NDTMCL3DNode::saveMap [private]

indicates if we want to save the map in a regular intervals

Definition at line 74 of file 3d_ndt_mcl_node.cpp.

Eigen::Affine3d NDTMCL3DNode::sensorPoseT [private]

Laser sensor offset.

Definition at line 67 of file 3d_ndt_mcl_node.cpp.

Definition at line 78 of file 3d_ndt_mcl_node.cpp.

Definition at line 83 of file 3d_ndt_mcl_node.cpp.

Eigen::Affine3d NDTMCL3DNode::Tcum [private]

Definition at line 68 of file 3d_ndt_mcl_node.cpp.

std::string NDTMCL3DNode::tf_base_link [private]

Definition at line 85 of file 3d_ndt_mcl_node.cpp.

std::string NDTMCL3DNode::tf_sensor_link [private]

Definition at line 85 of file 3d_ndt_mcl_node.cpp.

Eigen::Affine3d NDTMCL3DNode::Todo [private]

Definition at line 68 of file 3d_ndt_mcl_node.cpp.

Eigen::Affine3d NDTMCL3DNode::Todo_old [private]

Definition at line 68 of file 3d_ndt_mcl_node.cpp.

Eigen::Affine3d NDTMCL3DNode::Told [private]

Definition at line 68 of file 3d_ndt_mcl_node.cpp.


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


ndt_mcl
Author(s): Jari Saarinen
autogenerated on Wed Aug 26 2015 15:25:02