#include <unit_process.h>
|
geometry_msgs::Pose | computeCylinderPose (const Eigen::Vector3d &st_pt, const Eigen::Vector3d &end_pt) const |
|
moveit_msgs::CollisionObject | createCollisionObject (const int &id, const Eigen::Vector3d &st_pt, const Eigen::Vector3d &end_pt, const double &element_diameter, std::string &&shrink_type_suffix="") const |
|
void | createShrinkedEndPoint (Eigen::Vector3d &st_pt, Eigen::Vector3d &end_st, double shrink_length) |
|
Definition at line 15 of file unit_process.h.
choreo_task_sequence_processing_utils::UnitProcess::UnitProcess |
( |
int |
index, |
|
|
int |
wireframe_id, |
|
|
Eigen::Vector3d |
st_pt, |
|
|
Eigen::Vector3d |
end_pt, |
|
|
std::vector< Eigen::Vector3d > |
feasible_orients, |
|
|
std::string |
type_str, |
|
|
double |
element_diameter, |
|
|
double |
shrink_length, |
|
|
std::string |
world_frame |
|
) |
| |
|
inline |
virtual choreo_task_sequence_processing_utils::UnitProcess::~UnitProcess |
( |
| ) |
|
|
inlinevirtual |
choreo_msgs::ElementCandidatePoses choreo_task_sequence_processing_utils::UnitProcess::asElementCandidatePoses |
( |
| ) |
|
geometry_msgs::Pose choreo_task_sequence_processing_utils::UnitProcess::computeCylinderPose |
( |
const Eigen::Vector3d & |
st_pt, |
|
|
const Eigen::Vector3d & |
end_pt |
|
) |
| const |
|
protected |
moveit_msgs::CollisionObject choreo_task_sequence_processing_utils::UnitProcess::createCollisionObject |
( |
const int & |
id, |
|
|
const Eigen::Vector3d & |
st_pt, |
|
|
const Eigen::Vector3d & |
end_pt, |
|
|
const double & |
element_diameter, |
|
|
std::string && |
shrink_type_suffix = "" |
|
) |
| const |
|
protected |
void choreo_task_sequence_processing_utils::UnitProcess::createShrinkedEndPoint |
( |
Eigen::Vector3d & |
st_pt, |
|
|
Eigen::Vector3d & |
end_st, |
|
|
double |
shrink_length |
|
) |
| |
|
protected |
Eigen::Vector3d choreo_task_sequence_processing_utils::UnitProcess::getEndPt |
( |
| ) |
|
|
inline |
std::vector<Eigen::Vector3d> choreo_task_sequence_processing_utils::UnitProcess::getFeasibleOrients |
( |
| ) |
|
|
inline |
Eigen::Vector3d choreo_task_sequence_processing_utils::UnitProcess::getStartPt |
( |
| ) |
|
|
inline |
std::string choreo_task_sequence_processing_utils::UnitProcess::getType |
( |
| ) |
|
|
inline |
double choreo_task_sequence_processing_utils::UnitProcess::element_diameter_ |
|
private |
Eigen::Vector3d choreo_task_sequence_processing_utils::UnitProcess::end_pt_ |
|
private |
std::vector<Eigen::Vector3d> choreo_task_sequence_processing_utils::UnitProcess::feasible_orients_ |
|
private |
int choreo_task_sequence_processing_utils::UnitProcess::id_ |
|
private |
double choreo_task_sequence_processing_utils::UnitProcess::shrink_length_ |
|
private |
Eigen::Vector3d choreo_task_sequence_processing_utils::UnitProcess::st_pt_ |
|
private |
std::string choreo_task_sequence_processing_utils::UnitProcess::type_ |
|
private |
int choreo_task_sequence_processing_utils::UnitProcess::wireframe_id_ |
|
private |
std::string choreo_task_sequence_processing_utils::UnitProcess::world_frame_ |
|
private |
The documentation for this class was generated from the following files: