Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[octomap_server] Filtering In Base Frame Instead of Map Frame #83

Open
wants to merge 2 commits into
base: kinetic-devel
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
72 changes: 25 additions & 47 deletions octomap_server/src/OctomapServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -260,24 +260,29 @@ bool OctomapServer::openFile(const std::string& filename){

void OctomapServer::insertCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& cloud){
ros::WallTime startTime = ros::WallTime::now();


//
// ground filtering in base frame
//
PCLPointCloud pc; // input cloud for filtering and ground-detection
pcl::fromROSMsg(*cloud, pc);

tf::StampedTransform sensorToWorldTf;
tf::StampedTransform sensorToWorldTf, sensorToBaseTf, baseToWorldTf;
try {
m_tfListener.lookupTransform(m_worldFrameId, cloud->header.frame_id, cloud->header.stamp, sensorToWorldTf);
m_tfListener.waitForTransform(m_baseFrameId, cloud->header.frame_id, cloud->header.stamp, ros::Duration(0.2));
m_tfListener.lookupTransform(m_baseFrameId, cloud->header.frame_id, cloud->header.stamp, sensorToBaseTf);
m_tfListener.lookupTransform(m_worldFrameId, m_baseFrameId, cloud->header.stamp, baseToWorldTf);
} catch(tf::TransformException& ex){
ROS_ERROR_STREAM( "Transform error of sensor data: " << ex.what() << ", quitting callback");
ROS_ERROR_STREAM( "Transform error of sensor data: " << ex.what() << ", quitting callback.\n"
"You need to set base_frame_id to apply filtering.\n"
"Also check if transforms exist between map, sensor and base frames.");
return;
}

Eigen::Matrix4f sensorToWorld;
Eigen::Matrix4f sensorToWorld, sensorToBase, baseToWorld;
pcl_ros::transformAsMatrix(sensorToWorldTf, sensorToWorld);
pcl_ros::transformAsMatrix(sensorToBaseTf, sensorToBase);
pcl_ros::transformAsMatrix(baseToWorldTf, baseToWorld);


// set up filter for height range, also removes NANs:
Expand All @@ -294,55 +299,28 @@ void OctomapServer::insertCloudCallback(const sensor_msgs::PointCloud2::ConstPtr
PCLPointCloud pc_ground; // segmented ground plane
PCLPointCloud pc_nonground; // everything else

// transform pointcloud from sensor frame to fixed robot frame
pcl::transformPointCloud(pc, pc, sensorToBase);
pass_x.setInputCloud(pc.makeShared());
pass_x.filter(pc);
pass_y.setInputCloud(pc.makeShared());
pass_y.filter(pc);

if (m_filterGroundPlane){
tf::StampedTransform sensorToBaseTf, baseToWorldTf;
try{
m_tfListener.waitForTransform(m_baseFrameId, cloud->header.frame_id, cloud->header.stamp, ros::Duration(0.2));
m_tfListener.lookupTransform(m_baseFrameId, cloud->header.frame_id, cloud->header.stamp, sensorToBaseTf);
m_tfListener.lookupTransform(m_worldFrameId, m_baseFrameId, cloud->header.stamp, baseToWorldTf);


}catch(tf::TransformException& ex){
ROS_ERROR_STREAM( "Transform error for ground plane filter: " << ex.what() << ", quitting callback.\n"
"You need to set the base_frame_id or disable filter_ground.");
}


Eigen::Matrix4f sensorToBase, baseToWorld;
pcl_ros::transformAsMatrix(sensorToBaseTf, sensorToBase);
pcl_ros::transformAsMatrix(baseToWorldTf, baseToWorld);

// transform pointcloud from sensor frame to fixed robot frame
pcl::transformPointCloud(pc, pc, sensorToBase);
pass_x.setInputCloud(pc.makeShared());
pass_x.filter(pc);
pass_y.setInputCloud(pc.makeShared());
pass_y.filter(pc);
pass_z.setInputCloud(pc.makeShared());
pass_z.filter(pc);
filterGroundPlane(pc, pc_ground, pc_nonground);

// transform clouds to world frame for insertion
pcl::transformPointCloud(pc_ground, pc_ground, baseToWorld);
pcl::transformPointCloud(pc_nonground, pc_nonground, baseToWorld);
} else {
// directly transform to map frame:
pcl::transformPointCloud(pc, pc, sensorToWorld);

// just filter height range:
pass_x.setInputCloud(pc.makeShared());
pass_x.filter(pc);
pass_y.setInputCloud(pc.makeShared());
pass_y.filter(pc);
}
else {
pass_z.setInputCloud(pc.makeShared());
pass_z.filter(pc);

pc_nonground = pc;
// pc_nonground is empty without ground segmentation
pc_ground.header = pc.header;
pc_nonground.header = pc.header;
pass_z.filter(pc_nonground);
pass_z.setFilterLimitsNegative(true);
pass_z.filter(pc_ground);
}

// transform clouds to world frame for insertion
pcl::transformPointCloud(pc_ground, pc_ground, baseToWorld);
pcl::transformPointCloud(pc_nonground, pc_nonground, baseToWorld);

insertScan(sensorToWorldTf.getOrigin(), pc_ground, pc_nonground);

Expand Down