diff --git a/rslidar_pointcloud/CMakeLists.txt b/rslidar_pointcloud/CMakeLists.txt index 21bde31..ea37a89 100644 --- a/rslidar_pointcloud/CMakeLists.txt +++ b/rslidar_pointcloud/CMakeLists.txt @@ -5,6 +5,7 @@ add_compile_options(-std=c++11) set(CMAKE_BUILD_TYPE Release)#RelWithDebInfo set(${PROJECT_NAME}_CATKIN_DEPS angles + eigen_conversions nodelet pcl_ros roscpp diff --git a/rslidar_pointcloud/launch/rs_bpearl.launch b/rslidar_pointcloud/launch/rs_bpearl.launch index ee76ce0..a5970e8 100644 --- a/rslidar_pointcloud/launch/rs_bpearl.launch +++ b/rslidar_pointcloud/launch/rs_bpearl.launch @@ -23,6 +23,9 @@ + + + diff --git a/rslidar_pointcloud/package.xml b/rslidar_pointcloud/package.xml index 51bc6b1..bac8684 100644 --- a/rslidar_pointcloud/package.xml +++ b/rslidar_pointcloud/package.xml @@ -31,9 +31,11 @@ roslaunch rostest tf2_ros + eigen_conversions angles nodelet + eigen_conversions pcl_ros pluginlib diff --git a/rslidar_pointcloud/src/convert.cc b/rslidar_pointcloud/src/convert.cc index b5ea262..f7ecaf9 100644 --- a/rslidar_pointcloud/src/convert.cc +++ b/rslidar_pointcloud/src/convert.cc @@ -15,16 +15,33 @@ */ #include "convert.h" #include +#include namespace rslidar_pointcloud { std::string model; /** @brief Constructor. */ -Convert::Convert(ros::NodeHandle node, ros::NodeHandle private_nh) : data_(new rslidar_rawdata::RawData()) +Convert::Convert(ros::NodeHandle node, ros::NodeHandle private_nh) : + data_(new rslidar_rawdata::RawData()), + tf_buffer_(), + tf_listener_(tf_buffer_) { data_->loadConfigFile(node, private_nh); // load lidar parameters private_nh.param("model", model, std::string("RS16")); + private_nh.param("compensate_motion", compensate_motion_, false); + private_nh.param("fixed_frame", fixed_frame_, std::string("")); + private_nh.param("tf_wait_time", tf_wait_time_, 0.02); + + ROS_INFO_STREAM("[cloud][convert] compensate motion: " << compensate_motion_); + if (compensate_motion_) { + if (fixed_frame_.empty()) { + ROS_ERROR_STREAM("[cloud][convert] Motion compensation enabled but got empty fixed frame id"); + } else { + ROS_INFO_STREAM("[cloud][convert] fixed frame: " << fixed_frame_); + ROS_INFO_STREAM("[cloud][convert] Tf wait time: " << tf_wait_time_); + } + } // advertise output point cloud (before subscribing to input data) std::string output_points_topic; @@ -74,9 +91,31 @@ void Convert::processScan(const rslidar_msgs::rslidarScan::ConstPtr& scanMsg) // process each packet provided by the driver data_->block_num = 0; + geometry_msgs::TransformStamped tf_comp_stamped; + Eigen::Affine3d tf_comp_eigen; for (size_t i = 0; i < scanMsg->packets.size(); ++i) { - data_->unpack(scanMsg->packets[i], outPoints); + if (compensate_motion_) { + // Set transform to identity, in case transform lookup fails. + tf_comp_eigen.setIdentity(); + try{ + tf_comp_stamped = tf_buffer_.lookupTransform(scanMsg->header.frame_id, // Target frame. + scanMsg->header.stamp, // Target time. + scanMsg->header.frame_id, // Source frame. + scanMsg->packets[i].stamp, // Source time. + fixed_frame_, // Fixed frame. + ros::Duration(tf_wait_time_)); // Wait time for transform. + ROS_DEBUG_STREAM(tf_comp_stamped); + tf::transformMsgToEigen(tf_comp_stamped.transform, tf_comp_eigen); + } + catch (tf2::TransformException &ex) { + ROS_WARN("%s",ex.what()); + } + data_->unpack(scanMsg->packets[i], outPoints, tf_comp_eigen.cast()); + } else { + data_->unpack(scanMsg->packets[i], outPoints); + } + } sensor_msgs::PointCloud2 outMsg; pcl::toROSMsg(*outPoints, outMsg); diff --git a/rslidar_pointcloud/src/convert.h b/rslidar_pointcloud/src/convert.h index 93df091..07c7e7a 100644 --- a/rslidar_pointcloud/src/convert.h +++ b/rslidar_pointcloud/src/convert.h @@ -44,6 +44,13 @@ class Convert boost::shared_ptr data_; ros::Subscriber rslidar_scan_; ros::Publisher output_; + + // Motion compensation. + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + bool compensate_motion_; + std::string fixed_frame_; + double tf_wait_time_; }; } // namespace rslidar_pointcloud diff --git a/rslidar_pointcloud/src/rawdata.cc b/rslidar_pointcloud/src/rawdata.cc index cbe5c81..4ee7e9e 100644 --- a/rslidar_pointcloud/src/rawdata.cc +++ b/rslidar_pointcloud/src/rawdata.cc @@ -827,7 +827,9 @@ int RawData::estimateTemperature(float Temper) * @param pkt raw packet to unpack * @param pc shared pointer to point cloud (points are appended) */ -void RawData::unpack(const rslidar_msgs::rslidarPacket& pkt, pcl::PointCloud::Ptr pointcloud) +void RawData::unpack(const rslidar_msgs::rslidarPacket& pkt, + pcl::PointCloud::Ptr pointcloud, + const Eigen::Affine3f& tf_comp) { // check pkt header if (pkt.data[0] != 0x55 || pkt.data[1] != 0xAA || pkt.data[2] != 0x05 || pkt.data[3] != 0x0A) @@ -837,7 +839,7 @@ void RawData::unpack(const rslidar_msgs::rslidarPacket& pkt, pcl::PointCloudsin_lookup_table_[arg_horiz_orginal]; point.z = distance2 * this->sin_lookup_table_[arg_vert] + Rz_; point.intensity = intensity; + point = pcl::transformPoint(point, tf_comp); pointcloud->at(2 * this->block_num + firing, dsr) = point; } } @@ -959,7 +962,9 @@ void RawData::unpack(const rslidar_msgs::rslidarPacket& pkt, pcl::PointCloud::Ptr pointcloud) +void RawData::unpack_RS32(const rslidar_msgs::rslidarPacket& pkt, + pcl::PointCloud::Ptr pointcloud, + const Eigen::Affine3f& tf_comp) { float azimuth; // 0.01 dgree float intensity; @@ -1076,6 +1081,7 @@ void RawData::unpack_RS32(const rslidar_msgs::rslidarPacket& pkt, pcl::PointClou Rx_ * this->sin_lookup_table_[arg_horiz_orginal]; point.z = distance2 * this->sin_lookup_table_[arg_vert] + Rz_; point.intensity = intensity; + point = pcl::transformPoint(point, tf_comp); pointcloud->at(this->block_num, dsr) = point; } } diff --git a/rslidar_pointcloud/src/rawdata.h b/rslidar_pointcloud/src/rawdata.h index 083edc2..6c0479a 100644 --- a/rslidar_pointcloud/src/rawdata.h +++ b/rslidar_pointcloud/src/rawdata.h @@ -136,10 +136,14 @@ class RawData void loadConfigFile(ros::NodeHandle node, ros::NodeHandle private_nh); /*unpack the RS16 UDP packet and opuput PCL PointXYZI type*/ - void unpack(const rslidar_msgs::rslidarPacket& pkt, pcl::PointCloud::Ptr pointcloud); + void unpack(const rslidar_msgs::rslidarPacket& pkt, + pcl::PointCloud::Ptr pointcloud, + const Eigen::Affine3f& tf_comp = Eigen::Affine3f::Identity()); /*unpack the RS32 UDP packet and opuput PCL PointXYZI type*/ - void unpack_RS32(const rslidar_msgs::rslidarPacket& pkt, pcl::PointCloud::Ptr pointcloud); + void unpack_RS32(const rslidar_msgs::rslidarPacket& pkt, + pcl::PointCloud::Ptr pointcloud, + const Eigen::Affine3f& tf_comp = Eigen::Affine3f::Identity()); /*compute temperature*/ float computeTemperature(unsigned char bit1, unsigned char bit2);