Public Member Functions | |
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 |
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_ |
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 |
Definition at line 37 of file ndt_fuser_node.cpp.
NDTFuserNode::NDTFuserNode | ( | ros::NodeHandle | param_nh | ) | [inline] |
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
enable for LaserScan message input
Definition at line 77 of file ndt_fuser_node.cpp.
NDTFuserNode::~NDTFuserNode | ( | ) | [inline] |
Definition at line 174 of file ndt_fuser_node.cpp.
void NDTFuserNode::laserCallback | ( | const sensor_msgs::LaserScan::ConstPtr & | msg_in | ) | [inline] |
Definition at line 267 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 294 of file ndt_fuser_node.cpp.
void NDTFuserNode::points2Callback | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg_in | ) | [inline] |
Definition at line 219 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 231 of file ndt_fuser_node.cpp.
void NDTFuserNode::processFrame | ( | pcl::PointCloud< pcl::PointXYZ > & | cloud, |
Eigen::Affine3d | Tmotion | ||
) | [inline] |
Definition at line 179 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 205 of file ndt_fuser_node.cpp.
bool NDTFuserNode::beHMT [protected] |
Definition at line 59 of file ndt_fuser_node.cpp.
lslgeneric::NDTFuserHMT<pcl::PointXYZ>* NDTFuserNode::fuser [protected] |
Definition at line 56 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 57 of file ndt_fuser_node.cpp.
Eigen::Affine3d NDTFuserNode::last_odom [protected] |
Definition at line 74 of file ndt_fuser_node.cpp.
boost::mutex NDTFuserNode::m [protected] |
Definition at line 55 of file ndt_fuser_node.cpp.
std::string NDTFuserNode::map_dir [protected] |
Definition at line 57 of file ndt_fuser_node.cpp.
std::string NDTFuserNode::map_name [protected] |
Definition at line 57 of file ndt_fuser_node.cpp.
bool NDTFuserNode::match2D [protected] |
Definition at line 59 of file ndt_fuser_node.cpp.
bool NDTFuserNode::matchLaser [protected] |
Definition at line 59 of file ndt_fuser_node.cpp.
boost::mutex NDTFuserNode::message_m [protected] |
Definition at line 55 of file ndt_fuser_node.cpp.
double NDTFuserNode::min_laser_range_ [protected] |
Definition at line 58 of file ndt_fuser_node.cpp.
unsigned int NDTFuserNode::nb_added_clouds_ [protected] |
Definition at line 52 of file ndt_fuser_node.cpp.
ros::NodeHandle NDTFuserNode::nh_ [protected] |
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 57 of file ndt_fuser_node.cpp.
ros::Publisher NDTFuserNode::output_pub_ [protected] |
Definition at line 49 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 57 of file ndt_fuser_node.cpp.
Eigen::Affine3d NDTFuserNode::pose_ [protected] |
Definition at line 50 of file ndt_fuser_node.cpp.
double NDTFuserNode::pose_init_p [protected] |
Definition at line 61 of file ndt_fuser_node.cpp.
double NDTFuserNode::pose_init_r [protected] |
Definition at line 61 of file ndt_fuser_node.cpp.
double NDTFuserNode::pose_init_t [protected] |
Definition at line 61 of file ndt_fuser_node.cpp.
double NDTFuserNode::pose_init_x [protected] |
Definition at line 61 of file ndt_fuser_node.cpp.
double NDTFuserNode::pose_init_y [protected] |
Definition at line 61 of file ndt_fuser_node.cpp.
double NDTFuserNode::pose_init_z [protected] |
Definition at line 61 of file ndt_fuser_node.cpp.
laser_geometry::LaserProjection NDTFuserNode::projector_ [protected] |
Definition at line 65 of file ndt_fuser_node.cpp.
double NDTFuserNode::resolution [protected] |
Definition at line 58 of file ndt_fuser_node.cpp.
ros::ServiceServer NDTFuserNode::save_map_ [protected] |
Definition at line 72 of file ndt_fuser_node.cpp.
Eigen::Affine3d NDTFuserNode::sensor_pose_ [protected] |
Definition at line 50 of file ndt_fuser_node.cpp.
double NDTFuserNode::sensor_pose_p [protected] |
Definition at line 63 of file ndt_fuser_node.cpp.
double NDTFuserNode::sensor_pose_r [protected] |
Definition at line 63 of file ndt_fuser_node.cpp.
double NDTFuserNode::sensor_pose_t [protected] |
Definition at line 63 of file ndt_fuser_node.cpp.
double NDTFuserNode::sensor_pose_x [protected] |
Definition at line 63 of file ndt_fuser_node.cpp.
double NDTFuserNode::sensor_pose_y [protected] |
Definition at line 63 of file ndt_fuser_node.cpp.
double NDTFuserNode::sensor_pose_z [protected] |
Definition at line 63 of file ndt_fuser_node.cpp.
double NDTFuserNode::sensor_range [protected] |
Definition at line 58 of file ndt_fuser_node.cpp.
double NDTFuserNode::size_x [protected] |
Definition at line 58 of file ndt_fuser_node.cpp.
double NDTFuserNode::size_y [protected] |
Definition at line 58 of file ndt_fuser_node.cpp.
double NDTFuserNode::size_z [protected] |
Definition at line 58 of file ndt_fuser_node.cpp.
message_filters::Synchronizer< LaserOdomSync >* NDTFuserNode::sync_lo_ [protected] |
Definition at line 67 of file ndt_fuser_node.cpp.
message_filters::Synchronizer< LaserPoseSync >* NDTFuserNode::sync_lp_ [protected] |
Definition at line 68 of file ndt_fuser_node.cpp.
message_filters::Synchronizer< PointsOdomSync >* NDTFuserNode::sync_po_ [protected] |
Definition at line 70 of file ndt_fuser_node.cpp.
message_filters::Synchronizer< PointsPoseSync >* NDTFuserNode::sync_pp_ [protected] |
Definition at line 71 of file ndt_fuser_node.cpp.
Eigen::Affine3d NDTFuserNode::T [protected] |
Definition at line 50 of file ndt_fuser_node.cpp.
tf::TransformBroadcaster NDTFuserNode::tf_ [protected] |
Definition at line 48 of file ndt_fuser_node.cpp.
Eigen::Affine3d NDTFuserNode::this_odom [protected] |
Definition at line 74 of file ndt_fuser_node.cpp.
bool NDTFuserNode::useOdometry [protected] |
Definition at line 59 of file ndt_fuser_node.cpp.
double NDTFuserNode::varz [protected] |
Definition at line 53 of file ndt_fuser_node.cpp.
bool NDTFuserNode::visualize [protected] |
Definition at line 59 of file ndt_fuser_node.cpp.