PL_MPEP Class Reference

#include <planners/ik_mpep/PL_MPEP.h>

Inherits PL_Boolean_Output, and PL_OpenGL.

Inherited by PL_ForTest.

Inheritance diagram for PL_MPEP:

Inheritance graph
[legend]
Collaboration diagram for PL_MPEP:

Collaboration graph
[legend]
List of all members.

Public Member Functions

 PL_MPEP ()
virtual ~PL_MPEP ()
virtual void SetCollisionDetector (CD_BasicStyle *collisionDetector)
virtual bool DrawExplicit () const
virtual bool Plan ()
Frame GetToolFrame (const Configuration &config) const
void SetTrajectory (std::vector< Frame > &traj)
void SetPassiveNum (unsigned int num)
void SetAlgorithm (unsigned int alg)
void SetTolerance (double dist)
void SetUsingStartConfig (bool use)
void SetUsingGoalConfig (bool use)
void SetRandomRetry (unsigned int retry)
void SetExtendNum (unsigned int num)
void SetExploreNum (unsigned int num)
void SetIterationNum (unsigned int num)
void SetSMGNodeNum (unsigned int num)
void SetUsingJacobianExt (bool use)

Protected Member Functions

bool GetConfigurationByDirection (Configuration &conf, Configuration &base, Configuration &direct)
bool GetRandomConfiguration (Configuration &conf)
bool GetRandomConfiguration (Configuration &conf, Frame &frame)
bool GetRandomConfiguration (Configuration &conf, Frame &frame, Configuration &bias)
int Greedy_Step (int &begin, int end, vertex &base)
int RRT_Extend_Like (dynamic_trees &tr, std::vector< vertex > &vert, int &extPose, vertex &extended, int dir=1)
int Step (dynamic_trees &tr, std::vector< vertex > &vert, int begin, int end, vertex &base, int dir=1)
bool IsJointWithinLimits (Configuration &config)
bool AdjustConfiguration (Configuration &config, int nPose)
int Extend_Node_Self_Motion_Graph_Jacobian (vertex g_vertex, Configuration **nextConf)
int Establish_Self_Motion_Graph (dynamic_trees &tr, vertex extended)
int Extend_Node_Self_Motion_Graph (vertex g_vertex, Configuration **)
int CheckConnectivity (dynamic_trees &tr, std::vector< vertex > &vert, vertex extendedVert, vertex &connectedVert, int dir)
int Planner_Greedy ()
int Planner_RRT_Like ()
int Planner_RRT_Connect_Like ()
int Planner_RRT_Greedy_Like ()
int Planner_RRT_Greedy_Connect ()
int Planner_IMP_Greedy ()
int Planner_SMG_Greedy ()
int Planner_SMG_RRT_Connect_Like ()
int Planner_SMG_RRT_Greedy_Like ()
void ClearTree ()
int InitializeTree ()
void RetrievePathFromTree ()
vertex ConnectNode (dynamic_trees &tr, std::vector< vertex > &vert, vertex &parent, Pose_Node &child)
vertex GetNearestNodeInTree (dynamic_trees &tr, std::vector< vertex > &vert, Configuration &conf)
vertex GetClosestPoseVert (dynamic_trees &tr, std::vector< vertex > &vert)
void * GetNearestNodeInGraph (SMGraph *graph, Configuration *conf)
double Distance (Configuration &conf1, Configuration &conf2)
double DistanceInActiveJoints (Configuration &conf1, Configuration &conf2)
void Display_Error_Message (int result)

Protected Attributes

R_OpenChainm_pRobot
int m_nDof
int m_nToolFrame
Frame m_frEndEffector
CJacobianm_pJacobian
CRedundant redundant
vertex goalPoseVertex
vertex goalPoseVertex2
vertex startPoseVertex
dynamic_trees tree
std::vector< vertex > vertices
dynamic_trees goal_tree
std::vector< vertex > goal_vertices
std::vector< vertex > itinerary
std::vector< Frameposes
unsigned int algorithm
unsigned int passiveNum
unsigned int randomRetry
unsigned int extendNum
unsigned int exploreNum
unsigned int iterationNum
unsigned int smgNodeNum
double distTolerance
bool usingStartConfig
bool usingGoalConfig
bool usingGoalTree
bool usingJacobianExt

Detailed Description

Definition at line 89 of file PL_MPEP.h.


Constructor & Destructor Documentation

PL_MPEP::PL_MPEP  ) 
 

Definition at line 72 of file PL_MPEP.cpp.

References ALG_GREEDY_PLANNER, algorithm, ClearTree(), DEFAULT_EXPLORE_RETRY, DEFAULT_EXTEND_RETRY, DEFAULT_ITERATION, DEFAULT_RANDOM_RETRY, DEFAULT_SMGNODE_NUM, DEFAULT_TOLERANCE, distTolerance, exploreNum, extendNum, iterationNum, m_pJacobian, passiveNum, randomRetry, smgNodeNum, usingGoalConfig, usingGoalTree, usingJacobianExt, and usingStartConfig.

Here is the call graph for this function:

PL_MPEP::~PL_MPEP  )  [virtual]
 

Definition at line 90 of file PL_MPEP.cpp.

References ClearTree(), and m_pJacobian.

Here is the call graph for this function:


Member Function Documentation

bool PL_MPEP::AdjustConfiguration Configuration config,
int  nPose
[protected]
 

Reimplemented in PL_ForTest.

Definition at line 259 of file PL_MPEP.cpp.

References DEF_ERROR_TOLERANCE, CJacobian::GetMatrix(), GetToolFrame(), Frame::GetTranslationVector(), Matrixmxn::Inverse(), m_frEndEffector, m_nDof, m_pJacobian, Vector4::Magnitude(), poses, Rad2Deg(), CJacobian::SetConfiguration(), and CJacobian::SetInterestPoint().

Referenced by Extend_Node_Self_Motion_Graph_Jacobian().

Here is the call graph for this function:

int PL_MPEP::CheckConnectivity dynamic_trees &  tr,
std::vector< vertex > &  vert,
vertex  extendedVert,
vertex &  connectedVert,
int  dir
[protected]
 

Definition at line 552 of file PL_MPEP.cpp.

References PL_HasCollisionDetector::collisionDetector, Pose_Node::conf, SMGraph::FirstNode(), SMGraph::GetConfiguration(), Pose_Node::graph, CD_Linear::IsInterferingLinear(), SMGraph::NextNode(), Pose_Node::poses, and tree.

Referenced by Planner_SMG_RRT_Connect_Like().

Here is the call graph for this function:

void PL_MPEP::ClearTree  )  [protected]
 

Definition at line 1560 of file PL_MPEP.cpp.

References PlannerBase::guid, Semaphore::Lock(), numTotalNode, tree, and vertices.

Referenced by InitializeTree(), PL_MPEP(), and ~PL_MPEP().

Here is the call graph for this function:

vertex PL_MPEP::ConnectNode dynamic_trees &  tr,
std::vector< vertex > &  vert,
vertex &  parent,
Pose_Node child
[protected]
 

Definition at line 1594 of file PL_MPEP.cpp.

References Pose_Node::conf, Pose_Node::graph, PlannerBase::guid, Semaphore::Lock(), Pose_Node::poses, and Semaphore::Unlock().

Referenced by Greedy_Step(), and Step().

Here is the call graph for this function:

void PL_MPEP::Display_Error_Message int  result  )  [protected]
 

Definition at line 1908 of file PL_MPEP.cpp.

References ERROR_GET_COLLISION_FREE_FAILURE, ERROR_GET_RANDOM_CONF_FAILURE, ERROR_GOAL_CONFIG_INVALID, ERROR_PLANNING_TIMEOUT, ERROR_RRT_EXTEND_FAILURE, ERROR_SMGRAPH_FULL, and ERROR_START_CONFIG_INVALID.

double PL_MPEP::Distance Configuration conf1,
Configuration conf2
[protected]
 

Definition at line 1700 of file PL_MPEP.cpp.

References PL_HasCollisionDetector::collisionDetector, CD_JointLimits::JointDisplacement(), VectorN::Length(), and Sqr().

Here is the call graph for this function:

double PL_MPEP::DistanceInActiveJoints Configuration conf1,
Configuration conf2
[protected]
 

Definition at line 1714 of file PL_MPEP.cpp.

References PL_HasCollisionDetector::collisionDetector, CD_JointLimits::JointDisplacement(), VectorN::Length(), passiveNum, and Sqr().

Referenced by GetNearestNodeInGraph(), and GetNearestNodeInTree().

Here is the call graph for this function:

bool PL_MPEP::DrawExplicit  )  const [virtual]
 

Reimplemented from PL_OpenGL.

Reimplemented in PL_ForTest.

Definition at line 1941 of file PL_MPEP.cpp.

References SMGraph::GetConfig(), SMGraph::GetSMGraph(), Pose_Node::graph, Semaphore::Lock(), tree, and vertices.

Referenced by PL_ForTest::DrawExplicit().

Here is the call graph for this function:

int PL_MPEP::Establish_Self_Motion_Graph dynamic_trees &  tr,
vertex  extended
[protected]
 

Reimplemented in PL_ForTest.

Definition at line 470 of file PL_MPEP.cpp.

References Pose_Node::conf, ERROR_OK, Extend_Node_Self_Motion_Graph(), Extend_Node_Self_Motion_Graph_Jacobian(), Pose_Node::graph, SMGraph::Node_Num(), numFinalSMGNode, numFinalSMGraph, numSMGNode, numSMGraph, smgNodeNum, and usingJacobianExt.

Referenced by Planner_SMG_Greedy(), and Planner_SMG_RRT_Greedy_Like().

Here is the call graph for this function:

int PL_MPEP::Extend_Node_Self_Motion_Graph vertex  g_vertex,
Configuration ** 
[protected]
 

Reimplemented in PL_ForTest.

Definition at line 416 of file PL_MPEP.cpp.

References PL_HasCollisionDetector::collisionDetector, distTolerance, SMGraph::GetConfiguration(), CRedundant::GetConfigurationByActive(), GetConfigurationByDirection(), GetNearestNodeInGraph(), GetRandomConfiguration(), Pose_Node::graph, CD_Bool::IsInterfering(), CD_Linear::IsInterferingLinear(), Pose_Node::poses, poses, randomRetry, redundant, and tree.

Referenced by Establish_Self_Motion_Graph().

Here is the call graph for this function:

int PL_MPEP::Extend_Node_Self_Motion_Graph_Jacobian vertex  g_vertex,
Configuration **  nextConf
[protected]
 

Reimplemented in PL_ForTest.

Definition at line 317 of file PL_MPEP.cpp.

References AdjustConfiguration(), PL_HasCollisionDetector::collisionDetector, DEF_SMG_STEPSIZE, SMGraph::GetConfiguration(), CJacobian::GetMatrix(), GetNearestNodeInGraph(), GetRandomConfiguration(), Pose_Node::graph, Matrixmxn::Inverse(), CD_Bool::IsInterfering(), CD_Linear::IsInterferingLinear(), IsJointWithinLimits(), m_nDof, m_pJacobian, Pose_Node::poses, randomRetry, and tree.

Referenced by Establish_Self_Motion_Graph().

Here is the call graph for this function:

vertex PL_MPEP::GetClosestPoseVert dynamic_trees &  tr,
std::vector< vertex > &  vert
[protected]
 

Definition at line 1673 of file PL_MPEP.cpp.

References Pose_Node::poses.

Referenced by Planner_RRT_Greedy_Connect(), and Planner_RRT_Greedy_Like().

bool PL_MPEP::GetConfigurationByDirection Configuration conf,
Configuration base,
Configuration direct
[protected]
 

Definition at line 1729 of file PL_MPEP.cpp.

References PL_HasCollisionDetector::collisionDetector, CD_BasicStyle::DOF(), passiveNum, and VectorN::SetLength().

Referenced by Extend_Node_Self_Motion_Graph(), PL_ForTest::Extend_Node_Self_Motion_Graph(), and RRT_Extend_Like().

Here is the call graph for this function:

void * PL_MPEP::GetNearestNodeInGraph SMGraph graph,
Configuration conf
[protected]
 

Definition at line 1446 of file PL_MPEP.cpp.

References DistanceInActiveJoints(), Configuration::DOF(), SMGraph::FirstNode(), SMGraph::GetConfiguration(), and SMGraph::NextNode().

Referenced by Extend_Node_Self_Motion_Graph(), PL_ForTest::Extend_Node_Self_Motion_Graph(), Extend_Node_Self_Motion_Graph_Jacobian(), and PL_ForTest::Extend_Node_Self_Motion_Graph_Jacobian().

Here is the call graph for this function:

vertex PL_MPEP::GetNearestNodeInTree dynamic_trees &  tr,
std::vector< vertex > &  vert,
Configuration conf
[protected]
 

Definition at line 1420 of file PL_MPEP.cpp.

References Pose_Node::conf, and DistanceInActiveJoints().

Referenced by RRT_Extend_Like().

Here is the call graph for this function:

bool PL_MPEP::GetRandomConfiguration Configuration conf,
Frame frame,
Configuration bias
[protected]
 

Definition at line 1781 of file PL_MPEP.cpp.

References distTolerance, CRedundant::GetRandomConfiguration(), GetRandomConfiguration(), and redundant.

Here is the call graph for this function:

bool PL_MPEP::GetRandomConfiguration Configuration conf,
Frame frame
[protected]
 

Definition at line 1769 of file PL_MPEP.cpp.

References CRedundant::GetRandomConfiguration(), and redundant.

Here is the call graph for this function:

bool PL_MPEP::GetRandomConfiguration Configuration conf  )  [protected]
 

Definition at line 1758 of file PL_MPEP.cpp.

References CRedundant::GetRandomConfiguration(), and redundant.

Referenced by Extend_Node_Self_Motion_Graph(), PL_ForTest::Extend_Node_Self_Motion_Graph(), Extend_Node_Self_Motion_Graph_Jacobian(), PL_ForTest::Extend_Node_Self_Motion_Graph_Jacobian(), GetRandomConfiguration(), Greedy_Step(), RRT_Extend_Like(), and Step().

Here is the call graph for this function:

Frame PL_MPEP::GetToolFrame const Configuration config  )  const
 

Definition at line 102 of file PL_MPEP.cpp.

References CRedundant::GetDesireFrameByConfiguration(), and redundant.

Referenced by AdjustConfiguration(), PL_ForTest::AdjustConfiguration(), and PL_ForTest::FindLocalPath().

Here is the call graph for this function:

int PL_MPEP::Greedy_Step int &  begin,
int  end,
vertex &  base
[protected]
 

Definition at line 214 of file PL_MPEP.cpp.

References PL_HasCollisionDetector::collisionDetector, Pose_Node::conf, ConnectNode(), exploreNum, GetRandomConfiguration(), Pose_Node::graph, CD_Bool::IsInterfering(), CD_Linear::IsInterferingLinear(), Pose_Node::poses, poses, tree, and vertices.

Referenced by Planner_IMP_Greedy(), and Planner_SMG_Greedy().

Here is the call graph for this function:

int PL_MPEP::InitializeTree  )  [protected]
 

Definition at line 1473 of file PL_MPEP.cpp.

References _FIRST_POSE, ClearTree(), PL_HasCollisionDetector::collisionDetector, Pose_Node::conf, ERROR_START_CONFIG_INVALID, CRedundant::GetRandomConfiguration(), PlannerBase::GetStartConfig(), PlannerBase::guid, CD_Bool::IsInterfering(), poses, Pose_Node::poses, randomRetry, redundant, and usingStartConfig.

Referenced by Planner_Greedy(), Planner_IMP_Greedy(), Planner_RRT_Connect_Like(), Planner_RRT_Greedy_Connect(), Planner_RRT_Greedy_Like(), Planner_RRT_Like(), Planner_SMG_Greedy(), Planner_SMG_RRT_Connect_Like(), and Planner_SMG_RRT_Greedy_Like().

Here is the call graph for this function:

bool PL_MPEP::IsJointWithinLimits Configuration config  )  [protected]
 

Reimplemented in PL_ForTest.

Definition at line 300 of file PL_MPEP.cpp.

References PL_HasCollisionDetector::collisionDetector, CD_BasicStyle::JointMin(), and m_nDof.

Referenced by Extend_Node_Self_Motion_Graph_Jacobian().

Here is the call graph for this function:

bool PL_MPEP::Plan  )  [virtual]
 

Implements PlannerBase.

Reimplemented in PL_ForTest.

Definition at line 116 of file PL_MPEP.cpp.

References PA_Points::Clear(), PL_HasCollisionDetector::collisionDetector, ERROR_OK, ERROR_START_CONFIG_INVALID, PlannerBase::GetGoalConfig(), PlannerBase::GetStartConfig(), PlannerBase::goalConfig, CD_Bool::IsInterfering(), m_pJacobian, m_pRobot, numTotalNode, PL_Boolean_Output::path, PlannerBase::startConfig, and usingStartConfig.

Referenced by RRT_TrajPlanner::Plan().

Here is the call graph for this function:

int PL_MPEP::Planner_Greedy  )  [protected]
 

Definition at line 1036 of file PL_MPEP.cpp.

References _FIRST_POSE, _LAST_POSE, ERROR_OK, ERROR_PLANNING_TIMEOUT, goalPoseVertex, PlannerBase::HasTimeLimitExpired(), InitializeTree(), iterationNum, RetrievePathFromTree(), Step(), tree, usingGoalTree, and vertices.

Here is the call graph for this function:

int PL_MPEP::Planner_IMP_Greedy  )  [protected]
 

Definition at line 968 of file PL_MPEP.cpp.

References _FIRST_POSE, _LAST_POSE, ERROR_OK, ERROR_PLANNING_TIMEOUT, goalPoseVertex, Greedy_Step(), PlannerBase::HasTimeLimitExpired(), InitializeTree(), iterationNum, RetrievePathFromTree(), tree, usingGoalTree, and vertices.

Here is the call graph for this function:

int PL_MPEP::Planner_RRT_Connect_Like  )  [protected]
 

Definition at line 1144 of file PL_MPEP.cpp.

References _LAST_POSE, ERROR_OK, ERROR_PLANNING_TIMEOUT, ERROR_RRT_EXTEND_FAILURE, extendNum, goalPoseVertex, PlannerBase::HasTimeLimitExpired(), InitializeTree(), iterationNum, RetrievePathFromTree(), RRT_Extend_Like(), Step(), tree, usingGoalTree, and vertices.

Here is the call graph for this function:

int PL_MPEP::Planner_RRT_Greedy_Connect  )  [protected]
 

Definition at line 1269 of file PL_MPEP.cpp.

References _LAST_POSE, ERROR_OK, ERROR_PLANNING_TIMEOUT, ERROR_RRT_EXTEND_FAILURE, extendNum, GetClosestPoseVert(), goalPoseVertex, PlannerBase::HasTimeLimitExpired(), InitializeTree(), iterationNum, Pose_Node::poses, RetrievePathFromTree(), RRT_Extend_Like(), Step(), tree, usingGoalTree, and vertices.

Here is the call graph for this function:

int PL_MPEP::Planner_RRT_Greedy_Like  )  [protected]
 

Definition at line 1202 of file PL_MPEP.cpp.

References _LAST_POSE, ERROR_OK, ERROR_PLANNING_TIMEOUT, ERROR_RRT_EXTEND_FAILURE, extendNum, GetClosestPoseVert(), goalPoseVertex, PlannerBase::HasTimeLimitExpired(), InitializeTree(), iterationNum, Pose_Node::poses, RetrievePathFromTree(), RRT_Extend_Like(), Step(), tree, usingGoalTree, and vertices.

Here is the call graph for this function:

int PL_MPEP::Planner_RRT_Like  )  [protected]
 

Definition at line 1090 of file PL_MPEP.cpp.

References _FIRST_POSE, _LAST_POSE, ERROR_OK, ERROR_PLANNING_TIMEOUT, ERROR_RRT_EXTEND_FAILURE, extendNum, goalPoseVertex, PlannerBase::HasTimeLimitExpired(), InitializeTree(), iterationNum, RetrievePathFromTree(), RRT_Extend_Like(), tree, usingGoalTree, and vertices.

Here is the call graph for this function:

int PL_MPEP::Planner_SMG_Greedy  )  [protected]
 

Definition at line 880 of file PL_MPEP.cpp.

References _FIRST_POSE, _LAST_POSE, ERROR_OK, ERROR_PLANNING_TIMEOUT, Establish_Self_Motion_Graph(), PlannerBase::GetTimeElapsedInSeconds(), goalPoseVertex, Greedy_Step(), PlannerBase::HasTimeLimitExpired(), InitializeTree(), iterationNum, LogMessage, numFinalSMGNode, numFinalSMGraph, numSMGNode, numSMGraph, RetrievePathFromTree(), tree, usingGoalTree, and vertices.

Here is the call graph for this function:

int PL_MPEP::Planner_SMG_RRT_Connect_Like  )  [protected]
 

Definition at line 620 of file PL_MPEP.cpp.

References _FIRST_POSE, _LAST_POSE, CheckConnectivity(), ERROR_OK, ERROR_PLANNING_TIMEOUT, ERROR_RRT_EXTEND_FAILURE, extendNum, goal_tree, goal_vertices, goalPoseVertex, goalPoseVertex2, PlannerBase::HasTimeLimitExpired(), InitializeTree(), iterationNum, RetrievePathFromTree(), RRT_Extend_Like(), Step(), tree, usingGoalTree, and vertices.

Here is the call graph for this function:

int PL_MPEP::Planner_SMG_RRT_Greedy_Like  )  [protected]
 

Definition at line 778 of file PL_MPEP.cpp.

References _FIRST_POSE, _LAST_POSE, ERROR_OK, ERROR_PLANNING_TIMEOUT, ERROR_RRT_EXTEND_FAILURE, Establish_Self_Motion_Graph(), extendNum, goalPoseVertex, goalPoseVertex2, PlannerBase::HasTimeLimitExpired(), InitializeTree(), iterationNum, LogMessage, numFinalSMGNode, numFinalSMGraph, numSMGNode, numSMGraph, RetrievePathFromTree(), RRT_Extend_Like(), Step(), tree, usingGoalTree, and vertices.

Here is the call graph for this function:

void PL_MPEP::RetrievePathFromTree  )  [protected]
 

Definition at line 1613 of file PL_MPEP.cpp.

References PA_Points::AppendPoint(), goal_tree, goalPoseVertex, goalPoseVertex2, itinerary, numSMGNodeInPath, numSMGraphInPath, numTotalNode, PL_Boolean_Output::path, tree, usingGoalTree, and vertices.

Referenced by Planner_Greedy(), Planner_IMP_Greedy(), Planner_RRT_Connect_Like(), Planner_RRT_Greedy_Connect(), Planner_RRT_Greedy_Like(), Planner_RRT_Like(), Planner_SMG_Greedy(), Planner_SMG_RRT_Connect_Like(), and Planner_SMG_RRT_Greedy_Like().

Here is the call graph for this function:

int PL_MPEP::RRT_Extend_Like dynamic_trees &  tr,
std::vector< vertex > &  vert,
int &  extPose,
vertex &  extended,
int  dir = 1
[protected]
 

Definition at line 1323 of file PL_MPEP.cpp.

References PL_HasCollisionDetector::collisionDetector, Pose_Node::conf, distTolerance, CRedundant::GetConfigurationByActive(), GetConfigurationByDirection(), GetNearestNodeInTree(), GetRandomConfiguration(), CD_Bool::IsInterfering(), CD_Linear::IsInterferingLinear(), Pose_Node::poses, poses, and redundant.

Referenced by Planner_RRT_Connect_Like(), Planner_RRT_Greedy_Connect(), Planner_RRT_Greedy_Like(), Planner_RRT_Like(), Planner_SMG_RRT_Connect_Like(), and Planner_SMG_RRT_Greedy_Like().

Here is the call graph for this function:

void PL_MPEP::SetAlgorithm unsigned int  alg  ) 
 

Definition at line 1864 of file PL_MPEP.cpp.

References algorithm.

Referenced by RRT_TrajPlanner::Plan().

void PL_MPEP::SetCollisionDetector CD_BasicStyle collisionDetector  )  [virtual]
 

Reimplemented from PL_HasCollisionDetector.

Reimplemented in PL_ForTest.

Definition at line 1797 of file PL_MPEP.cpp.

References PL_HasCollisionDetector::collisionDetector, CD_BasicStyle::DOF(), CD_BasicStyle::GetFrameManager(), FrameManager::GetFrameRef(), CD_BasicStyle::GetRobot(), R_OpenChain::GetToolFrame(), Matrix4x4::Identity(), m_frEndEffector, m_nDof, m_nToolFrame, m_pJacobian, m_pRobot, redundant, CRedundant::SetActiveBaseFrame(), CRedundant::SetActiveFirstJoint(), CRedundant::SetActiveLastJoint(), CRedundant::SetCollisionDetector(), PL_HasCollisionDetector::SetCollisionDetector(), CRedundant::SetFrameManager(), CRedundant::SetPassiveBaseFrame(), CRedundant::SetPassiveFirstJoint(), and CRedundant::SetPassiveLastJoint().

Referenced by ServerBase::RefreshPlanner(), PL_ForTest::SetCollisionDetector(), and RRT_TrajPlanner::SetCollisionDetector().

Here is the call graph for this function:

void PL_MPEP::SetExploreNum unsigned int  num  ) 
 

Definition at line 1840 of file PL_MPEP.cpp.

References exploreNum.

Referenced by RRT_TrajPlanner::Plan().

void PL_MPEP::SetExtendNum unsigned int  num  ) 
 

Definition at line 1845 of file PL_MPEP.cpp.

References extendNum.

Referenced by RRT_TrajPlanner::Plan().

void PL_MPEP::SetIterationNum unsigned int  num  ) 
 

Definition at line 1835 of file PL_MPEP.cpp.

References iterationNum.

Referenced by RRT_TrajPlanner::Plan().

void PL_MPEP::SetPassiveNum unsigned int  num  ) 
 

Definition at line 1850 of file PL_MPEP.cpp.

References PL_HasCollisionDetector::collisionDetector, CD_BasicStyle::DOF(), passiveNum, redundant, CRedundant::SetActiveBaseFrame(), CRedundant::SetActiveFirstJoint(), CRedundant::SetActiveLastJoint(), CRedundant::SetPassiveBaseFrame(), CRedundant::SetPassiveFirstJoint(), and CRedundant::SetPassiveLastJoint().

Referenced by RRT_TrajPlanner::Plan().

Here is the call graph for this function:

void PL_MPEP::SetRandomRetry unsigned int  retry  ) 
 

Definition at line 1898 of file PL_MPEP.cpp.

Referenced by RRT_TrajPlanner::Plan().

void PL_MPEP::SetSMGNodeNum unsigned int  num  ) 
 

void PL_MPEP::SetTolerance double  dist  ) 
 

Definition at line 1883 of file PL_MPEP.cpp.

References distTolerance.

Referenced by RRT_TrajPlanner::Plan().

void PL_MPEP::SetTrajectory std::vector< Frame > &  traj  ) 
 

Definition at line 1869 of file PL_MPEP.cpp.

References poses.

Referenced by RRT_TrajPlanner::SetTrajectory().

void PL_MPEP::SetUsingGoalConfig bool  use  ) 
 

Definition at line 1893 of file PL_MPEP.cpp.

References usingGoalConfig.

Referenced by RRT_TrajPlanner::Plan().

void PL_MPEP::SetUsingJacobianExt bool  use  ) 
 

Definition at line 1878 of file PL_MPEP.cpp.

References usingJacobianExt.

void PL_MPEP::SetUsingStartConfig bool  use  ) 
 

Definition at line 1888 of file PL_MPEP.cpp.

References usingStartConfig.

Referenced by RRT_TrajPlanner::Plan().

int PL_MPEP::Step dynamic_trees &  tr,
std::vector< vertex > &  vert,
int  begin,
int  end,
vertex &  base,
int  dir = 1
[protected]
 

Definition at line 1367 of file PL_MPEP.cpp.

References PL_HasCollisionDetector::collisionDetector, Pose_Node::conf, ConnectNode(), exploreNum, GetRandomConfiguration(), Pose_Node::graph, CD_Bool::IsInterfering(), CD_Linear::IsInterferingLinear(), Pose_Node::poses, and poses.

Referenced by Planner_Greedy(), Planner_RRT_Connect_Like(), Planner_RRT_Greedy_Connect(), Planner_RRT_Greedy_Like(), Planner_SMG_RRT_Connect_Like(), and Planner_SMG_RRT_Greedy_Like().

Here is the call graph for this function:


Member Data Documentation

unsigned int PL_MPEP::algorithm [protected]
 

Definition at line 222 of file PL_MPEP.h.

Referenced by PL_MPEP(), and SetAlgorithm().

double PL_MPEP::distTolerance [protected]
 

Definition at line 229 of file PL_MPEP.h.

Referenced by Extend_Node_Self_Motion_Graph(), PL_ForTest::Extend_Node_Self_Motion_Graph(), GetRandomConfiguration(), PL_MPEP(), RRT_Extend_Like(), and SetTolerance().

unsigned int PL_MPEP::exploreNum [protected]
 

Definition at line 226 of file PL_MPEP.h.

Referenced by Greedy_Step(), PL_MPEP(), SetExploreNum(), and Step().

unsigned int PL_MPEP::extendNum [protected]
 

Definition at line 225 of file PL_MPEP.h.

Referenced by PL_MPEP(), Planner_RRT_Connect_Like(), Planner_RRT_Greedy_Connect(), Planner_RRT_Greedy_Like(), Planner_RRT_Like(), Planner_SMG_RRT_Connect_Like(), Planner_SMG_RRT_Greedy_Like(), and SetExtendNum().

dynamic_trees PL_MPEP::goal_tree [protected]
 

Definition at line 211 of file PL_MPEP.h.

Referenced by Planner_SMG_RRT_Connect_Like(), and RetrievePathFromTree().

std::vector<vertex> PL_MPEP::goal_vertices [protected]
 

Definition at line 212 of file PL_MPEP.h.

Referenced by Planner_SMG_RRT_Connect_Like().

vertex PL_MPEP::goalPoseVertex [protected]
 

Definition at line 195 of file PL_MPEP.h.

Referenced by Planner_Greedy(), Planner_IMP_Greedy(), Planner_RRT_Connect_Like(), Planner_RRT_Greedy_Connect(), Planner_RRT_Greedy_Like(), Planner_RRT_Like(), Planner_SMG_Greedy(), Planner_SMG_RRT_Connect_Like(), Planner_SMG_RRT_Greedy_Like(), and RetrievePathFromTree().

vertex PL_MPEP::goalPoseVertex2 [protected]
 

Definition at line 196 of file PL_MPEP.h.

Referenced by Planner_SMG_RRT_Connect_Like(), Planner_SMG_RRT_Greedy_Like(), and RetrievePathFromTree().

unsigned int PL_MPEP::iterationNum [protected]
 

Definition at line 227 of file PL_MPEP.h.

Referenced by PL_MPEP(), Planner_Greedy(), Planner_IMP_Greedy(), Planner_RRT_Connect_Like(), Planner_RRT_Greedy_Connect(), Planner_RRT_Greedy_Like(), Planner_RRT_Like(), Planner_SMG_Greedy(), Planner_SMG_RRT_Connect_Like(), Planner_SMG_RRT_Greedy_Like(), and SetIterationNum().

std::vector<vertex> PL_MPEP::itinerary [protected]
 

Definition at line 215 of file PL_MPEP.h.

Referenced by RetrievePathFromTree().

Frame PL_MPEP::m_frEndEffector [protected]
 

Reimplemented in PL_ForTest.

Definition at line 187 of file PL_MPEP.h.

Referenced by AdjustConfiguration(), and SetCollisionDetector().

int PL_MPEP::m_nDof [protected]
 

Reimplemented in PL_ForTest.

Definition at line 185 of file PL_MPEP.h.

Referenced by AdjustConfiguration(), Extend_Node_Self_Motion_Graph_Jacobian(), IsJointWithinLimits(), and SetCollisionDetector().

int PL_MPEP::m_nToolFrame [protected]
 

Reimplemented in PL_ForTest.

Definition at line 186 of file PL_MPEP.h.

Referenced by SetCollisionDetector().

CJacobian* PL_MPEP::m_pJacobian [protected]
 

Reimplemented in PL_ForTest.

Definition at line 188 of file PL_MPEP.h.

Referenced by AdjustConfiguration(), Extend_Node_Self_Motion_Graph_Jacobian(), PL_MPEP(), Plan(), SetCollisionDetector(), and ~PL_MPEP().

R_OpenChain* PL_MPEP::m_pRobot [protected]
 

Reimplemented in PL_ForTest.

Definition at line 184 of file PL_MPEP.h.

Referenced by Plan(), and SetCollisionDetector().

unsigned int PL_MPEP::passiveNum [protected]
 

Definition at line 223 of file PL_MPEP.h.

Referenced by DistanceInActiveJoints(), GetConfigurationByDirection(), PL_MPEP(), and SetPassiveNum().

std::vector<Frame> PL_MPEP::poses [protected]
 

Definition at line 219 of file PL_MPEP.h.

Referenced by AdjustConfiguration(), PL_ForTest::AdjustConfiguration(), Extend_Node_Self_Motion_Graph(), PL_ForTest::Extend_Node_Self_Motion_Graph(), PL_ForTest::FindLocalPath(), PL_ForTest::FindLocalPath2(), Greedy_Step(), InitializeTree(), RRT_Extend_Like(), SetTrajectory(), and Step().

unsigned int PL_MPEP::randomRetry [protected]
 

Definition at line 224 of file PL_MPEP.h.

Referenced by Extend_Node_Self_Motion_Graph(), PL_ForTest::Extend_Node_Self_Motion_Graph(), Extend_Node_Self_Motion_Graph_Jacobian(), PL_ForTest::Extend_Node_Self_Motion_Graph_Jacobian(), InitializeTree(), and PL_MPEP().

CRedundant PL_MPEP::redundant [protected]
 

Definition at line 192 of file PL_MPEP.h.

Referenced by Extend_Node_Self_Motion_Graph(), PL_ForTest::Extend_Node_Self_Motion_Graph(), GetRandomConfiguration(), GetToolFrame(), InitializeTree(), RRT_Extend_Like(), SetCollisionDetector(), and SetPassiveNum().

unsigned int PL_MPEP::smgNodeNum [protected]
 

Definition at line 228 of file PL_MPEP.h.

Referenced by Establish_Self_Motion_Graph(), PL_ForTest::Establish_Self_Motion_Graph(), PL_ForTest::PL_ForTest(), and PL_MPEP().

vertex PL_MPEP::startPoseVertex [protected]
 

Definition at line 201 of file PL_MPEP.h.

dynamic_trees PL_MPEP::tree [protected]
 

Definition at line 206 of file PL_MPEP.h.

Referenced by CheckConnectivity(), ClearTree(), DrawExplicit(), Extend_Node_Self_Motion_Graph(), PL_ForTest::Extend_Node_Self_Motion_Graph(), Extend_Node_Self_Motion_Graph_Jacobian(), PL_ForTest::Extend_Node_Self_Motion_Graph_Jacobian(), Greedy_Step(), Planner_Greedy(), Planner_IMP_Greedy(), Planner_RRT_Connect_Like(), Planner_RRT_Greedy_Connect(), Planner_RRT_Greedy_Like(), Planner_RRT_Like(), Planner_SMG_Greedy(), Planner_SMG_RRT_Connect_Like(), Planner_SMG_RRT_Greedy_Like(), PL_ForTest::RemoveNode(), and RetrievePathFromTree().

bool PL_MPEP::usingGoalConfig [protected]
 

Definition at line 231 of file PL_MPEP.h.

Referenced by PL_MPEP(), PL_ForTest::Plan(), and SetUsingGoalConfig().

bool PL_MPEP::usingGoalTree [protected]
 

Definition at line 232 of file PL_MPEP.h.

Referenced by PL_MPEP(), Planner_Greedy(), Planner_IMP_Greedy(), Planner_RRT_Connect_Like(), Planner_RRT_Greedy_Connect(), Planner_RRT_Greedy_Like(), Planner_RRT_Like(), Planner_SMG_Greedy(), Planner_SMG_RRT_Connect_Like(), Planner_SMG_RRT_Greedy_Like(), and RetrievePathFromTree().

bool PL_MPEP::usingJacobianExt [protected]
 

Definition at line 233 of file PL_MPEP.h.

Referenced by Establish_Self_Motion_Graph(), PL_MPEP(), and SetUsingJacobianExt().

bool PL_MPEP::usingStartConfig [protected]
 

Definition at line 230 of file PL_MPEP.h.

Referenced by InitializeTree(), PL_MPEP(), Plan(), PL_ForTest::Plan(), and SetUsingStartConfig().

std::vector<vertex> PL_MPEP::vertices [protected]
 

Definition at line 207 of file PL_MPEP.h.

Referenced by ClearTree(), DrawExplicit(), Greedy_Step(), PL_ForTest::LogStatistics(), Planner_Greedy(), Planner_IMP_Greedy(), Planner_RRT_Connect_Like(), Planner_RRT_Greedy_Connect(), Planner_RRT_Greedy_Like(), Planner_RRT_Like(), Planner_SMG_Greedy(), Planner_SMG_RRT_Connect_Like(), Planner_SMG_RRT_Greedy_Like(), and RetrievePathFromTree().


The documentation for this class was generated from the following files:
Generated on Sat Apr 1 21:56:12 2006 for Motion Planning Kernel by  doxygen 1.4.6-NO