hiep sua ten file
This commit is contained in:
@@ -40,8 +40,8 @@
|
||||
#include <Eigen/Core> // NOLINT (cpplint cannot handle include order here)
|
||||
|
||||
#include "tf3/buffer_core.h"
|
||||
#include <sensor_msgs/LaserScan.h>
|
||||
#include <sensor_msgs/PointCloud2.h>
|
||||
#include <robot_sensor_msgs/LaserScan.h>
|
||||
#include <robot_sensor_msgs/PointCloud2.h>
|
||||
#include <robot_geometry_msgs/TransformStamped.h>
|
||||
#include "laser_geometry/visibility_control.hpp"
|
||||
|
||||
@@ -104,7 +104,7 @@ public:
|
||||
LaserProjection()
|
||||
: angle_min_(0), angle_max_(0) {}
|
||||
|
||||
// Project a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2
|
||||
// Project a robot_sensor_msgs::LaserScan into a robot_sensor_msgs::PointCloud2
|
||||
/*!
|
||||
* Project a single laser scan from a linear array into a 3D
|
||||
* point cloud. The generated cloud will be in the same frame
|
||||
@@ -122,15 +122,15 @@ public:
|
||||
*/
|
||||
LASER_GEOMETRY_PUBLIC
|
||||
void projectLaser(
|
||||
const sensor_msgs::LaserScan & scan_in,
|
||||
sensor_msgs::PointCloud2 & cloud_out,
|
||||
const robot_sensor_msgs::LaserScan & scan_in,
|
||||
robot_sensor_msgs::PointCloud2 & cloud_out,
|
||||
double range_cutoff = -1.0,
|
||||
int channel_options = channel_option::Default)
|
||||
{
|
||||
projectLaser_(scan_in, cloud_out, range_cutoff, channel_options);
|
||||
}
|
||||
|
||||
// Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame
|
||||
// Transform a robot_sensor_msgs::LaserScan into a robot_sensor_msgs::PointCloud2 in target frame
|
||||
/*!
|
||||
* Transform a single laser scan from a linear array into a 3D
|
||||
* point cloud, accounting for movement of the laser over the
|
||||
@@ -155,8 +155,8 @@ public:
|
||||
LASER_GEOMETRY_PUBLIC
|
||||
void transformLaserScanToPointCloud(
|
||||
const std::string & target_frame,
|
||||
const sensor_msgs::LaserScan & scan_in,
|
||||
sensor_msgs::PointCloud2 & cloud_out,
|
||||
const robot_sensor_msgs::LaserScan & scan_in,
|
||||
robot_sensor_msgs::PointCloud2 & cloud_out,
|
||||
tf3::BufferCore & tf,
|
||||
double range_cutoff = -1.0,
|
||||
int channel_options = channel_option::Default)
|
||||
@@ -168,16 +168,16 @@ public:
|
||||
private:
|
||||
// Internal hidden representation of projectLaser
|
||||
void projectLaser_(
|
||||
const sensor_msgs::LaserScan & scan_in,
|
||||
sensor_msgs::PointCloud2 & cloud_out,
|
||||
const robot_sensor_msgs::LaserScan & scan_in,
|
||||
robot_sensor_msgs::PointCloud2 & cloud_out,
|
||||
double range_cutoff,
|
||||
int channel_options);
|
||||
|
||||
// Internal hidden representation of transformLaserScanToPointCloud2
|
||||
void transformLaserScanToPointCloud_(
|
||||
const std::string & target_frame,
|
||||
const sensor_msgs::LaserScan & scan_in,
|
||||
sensor_msgs::PointCloud2 & cloud_out,
|
||||
const robot_sensor_msgs::LaserScan & scan_in,
|
||||
robot_sensor_msgs::PointCloud2 & cloud_out,
|
||||
tf3::BufferCore & tf,
|
||||
double range_cutoff,
|
||||
int channel_options);
|
||||
@@ -185,8 +185,8 @@ private:
|
||||
// Function used by the several forms of transformLaserScanToPointCloud_
|
||||
void transformLaserScanToPointCloud_(
|
||||
const std::string & target_frame,
|
||||
const sensor_msgs::LaserScan & scan_in,
|
||||
sensor_msgs::PointCloud2 & cloud_out,
|
||||
const robot_sensor_msgs::LaserScan & scan_in,
|
||||
robot_sensor_msgs::PointCloud2 & cloud_out,
|
||||
tf3::Quaternion quat_start,
|
||||
tf3::Vector3 origin_start,
|
||||
tf3::Quaternion quat_end,
|
||||
|
||||
Reference in New Issue
Block a user