#include <sampled_trajectory.h>
◆ SampledTrajectory3D() [1/3]
sampled_traj::SampledTrajectory3D::SampledTrajectory3D |
( |
const double & |
dt, |
|
|
const polynomials::Trajectory3D & |
poly_trajectories |
|
) |
| |
◆ SampledTrajectory3D() [2/3]
sampled_traj::SampledTrajectory3D::SampledTrajectory3D |
( |
const std::vector< double > & |
time_vec, |
|
|
const pcl::PointCloud< pcl::PointXYZ > & |
pos_vec |
|
) |
| |
◆ SampledTrajectory3D() [3/3]
sampled_traj::SampledTrajectory3D::SampledTrajectory3D |
( |
| ) |
|
◆ Bresenham()
void sampled_traj::SampledTrajectory3D::Bresenham |
( |
const Eigen::Vector3d & |
p0, |
|
|
const Eigen::Vector3d & |
pf, |
|
|
std::vector< octomap::point3d > * |
points |
|
) |
| |
◆ ClearObject()
void sampled_traj::SampledTrajectory3D::ClearObject |
( |
| ) |
|
◆ CompressedVisMarkers()
void sampled_traj::SampledTrajectory3D::CompressedVisMarkers |
( |
visualization_msgs::MarkerArray * |
marker_array | ) |
|
◆ CompressSamples()
void sampled_traj::SampledTrajectory3D::CompressSamples |
( |
| ) |
|
◆ CreateKdTree()
void sampled_traj::SampledTrajectory3D::CreateKdTree |
( |
| ) |
|
◆ DeleteSample()
void sampled_traj::SampledTrajectory3D::DeleteSample |
( |
const int & |
index | ) |
|
◆ PrintSamples()
void sampled_traj::SampledTrajectory3D::PrintSamples |
( |
| ) |
|
◆ SamplesVisMarkers()
void sampled_traj::SampledTrajectory3D::SamplesVisMarkers |
( |
visualization_msgs::MarkerArray * |
marker_array | ) |
|
◆ SetMaxDev()
void sampled_traj::SampledTrajectory3D::SetMaxDev |
( |
const double & |
max_dev | ) |
|
◆ SetResolution()
void sampled_traj::SampledTrajectory3D::SetResolution |
( |
const double & |
resolution | ) |
|
◆ SortCollisions()
void sampled_traj::SampledTrajectory3D::SortCollisions |
( |
const std::vector< octomap::point3d > & |
colliding_nodes, |
|
|
std::vector< geometry_msgs::PointStamped > * |
samples |
|
) |
| |
◆ ThickBresenham()
void sampled_traj::SampledTrajectory3D::ThickBresenham |
( |
const Eigen::Vector3d & |
p0, |
|
|
const Eigen::Vector3d & |
pf |
|
) |
| |
◆ ThickTrajToPcl()
void sampled_traj::SampledTrajectory3D::ThickTrajToPcl |
( |
| ) |
|
◆ TrajVisMarkers()
void sampled_traj::SampledTrajectory3D::TrajVisMarkers |
( |
visualization_msgs::MarkerArray * |
marker_array | ) |
|
◆ cloud_ptr_
pcl::PointCloud<pcl::PointXYZ>::Ptr sampled_traj::SampledTrajectory3D::cloud_ptr_ |
Initial value:=
pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>)
◆ compressed_pos_
std::vector<Eigen::Vector3d> sampled_traj::SampledTrajectory3D::compressed_pos_ |
◆ compressed_time_
std::vector<double> sampled_traj::SampledTrajectory3D::compressed_time_ |
◆ kdtree_pos_
pcl::KdTreeFLANN<pcl::PointXYZ> sampled_traj::SampledTrajectory3D::kdtree_pos_ |
◆ max_dev_
double sampled_traj::SampledTrajectory3D::max_dev_ |
◆ n_compressed_points_
int sampled_traj::SampledTrajectory3D::n_compressed_points_ |
◆ n_points_
int sampled_traj::SampledTrajectory3D::n_points_ |
◆ point_cloud_traj_
pcl::PointCloud< pcl::PointXYZ > sampled_traj::SampledTrajectory3D::point_cloud_traj_ |
◆ pos_
pcl::PointCloud<pcl::PointXYZ> sampled_traj::SampledTrajectory3D::pos_ |
◆ resolution_
double sampled_traj::SampledTrajectory3D::resolution_ |
◆ thick_traj_
octomap::OcTree sampled_traj::SampledTrajectory3D::thick_traj_ = octomap::OcTree(0.1) |
◆ thickness_
double sampled_traj::SampledTrajectory3D::thickness_ |
◆ time_
std::vector<double> sampled_traj::SampledTrajectory3D::time_ |
The documentation for this class was generated from the following files: