Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
PathEngine::PathPlanner Class Reference

計画経路エンジン More...

#include <PathPlanner.h>

Public Member Functions

void boundingBoxMode (bool mode)
 
bool calcPath ()
 経路計画を行う More...
 
bool checkCollision ()
 現在の状態で干渉検出を行う More...
 
bool checkCollision (const Configuration &pos)
 干渉検出を行う More...
 
bool checkCollision (const std::vector< Configuration > &path)
 パスの干渉検出を行う More...
 
const std::pair< std::string, std::string > & collidingPair ()
 
unsigned int countCollisionCheck () const
 干渉チェックを呼び出した回数を取得する More...
 
AlgorithmgetAlgorithm ()
 計画アルゴリズムを取得する More...
 
void getAlgorithmNames (std::vector< std::string > &algorithms)
 経路計画アルゴリズム名の一覧を取得する More...
 
ConfigurationSpacegetConfigurationSpace ()
 コンフィギュレーション空間設定を取得する More...
 
MobilitygetMobility ()
 移動能力を取得する More...
 
void getMobilityNames (std::vector< std::string > &mobilitys)
 移動能力名の一覧を取得する More...
 
void getOptimizerNames (std::vector< std::string > &optimizers)
 経路最適化アルゴリズム名の一覧を取得する More...
 
std::vector< ConfigurationgetPath ()
 計画された経路の補間されたものを取得する More...
 
bool getProperties (const std::string &algorithm, std::vector< std::string > &names, std::vector< std::string > &values)
 経路計画アルゴリズムのプロパティ名一覧を取得する More...
 
RoadmapPtr getRoadmap ()
 ロードマップを取得する More...
 
std::vector< Configuration > & getWayPoints ()
 計画された経路を取得する More...
 
void getWorldState (OpenHRP::WorldState_out wstate)
 物理世界の状況を取得する More...
 
void initPlanner (const std::string &nameServer)
 初期化。NameServer, ModelLoaderとの接続を行う。 More...
 
void initSimulation ()
 動力学シミュレータを初期化する More...
 
bool optimize (const std::string &optimizer)
 指定した方法で経路を最適化する More...
 
 PathPlanner (unsigned int dim, WorldPtr world=WorldPtr(), bool isDebugMode=false)
 コンストラクタ More...
 
void registerAlgorithm (const std::string &algorithmName, AlgorithmNewFunc newFunc, AlgorithmDeleteFunc deleteFunc)
 経路計画アルゴリズムの登録 More...
 
hrp::BodyPtr registerCharacter (const char *name, OpenHRP::BodyInfo_ptr cInfo)
 キャラクタを動力学シミュレータに登録する。 More...
 
hrp::BodyPtr registerCharacter (const char *name, hrp::BodyPtr i_body)
 キャラクタを動力学シミュレータに登録する。 More...
 
hrp::BodyPtr registerCharacterByURL (const char *name, const char *url)
 キャラクタを動力学シミュレータに登録する。 More...
 
void registerIntersectionCheckPair (const char *char1, const char *name1, const char *char2, const char *name2, CORBA::Double tolerance)
 衝突検出ペアを設定する More...
 
void registerMobility (const std::string &mobilityName, MobilityNewFunc newFunc, MobilityDeleteFunc deleteFunc)
 移動能力の登録 More...
 
void registerOptimizer (const std::string &optimizerName, OptimizerNewFunc newFunc, OptimizerDeleteFunc deleteFunc)
 経路最適化アルゴリズムの登録 More...
 
hrp::BodyPtr robot ()
 ロボットを取得する More...
 
void setAlgorithmName (const std::string &algorithm)
 使用する経路計画アルゴリズム名を指定する More...
 
void setApplyConfigFunc (applyConfigFunc i_func)
 コンフィギュレーションベクトルからロボットの姿勢をセットする関数をセットする More...
 
void setCharacterPosition (const char *character, const OpenHRP::DblSequence &pos)
 位置を設定する More...
 
void setCollisionDetector (CollisionDetector *i_cd)
 
bool setConfiguration (const Configuration &pos)
 コンフィギュレーションをセットする More...
 
void setDebug (bool debug)
 デバッグモードの変更 More...
 
void setGoalConfiguration (const Configuration &pos)
 ゴール位置を設定する More...
 
bool setMobilityName (const std::string &mobility)
 使用する移動能力を設定する More...
 
void setPointCloud (const std::vector< hrp::Vector3 > &i_cloud, double i_radius)
 干渉チェック対象となるポイントクラウドを設定する More...
 
void setProperties (const std::map< std::string, std::string > &properties)
 アルゴリズムに対して各種情報を設定する More...
 
void setRobotName (const std::string &model)
 移動動作の設計対象にするモデルを設定する More...
 
void setStartConfiguration (const Configuration &pos)
 スタート位置を設定する More...
 
void stopPlanning ()
 計算を中止する More...
 
double timeCollisionCheck () const
 干渉チェックに使用した時間[s]を取得する More...
 
double timeForwardKinematics () const
 
WorldPtr world ()
 物理世界を取得する More...
 
 ~PathPlanner ()
 デストラクタ More...
 

Private Types

typedef std::map< const std::string, std::pair< AlgorithmNewFunc, AlgorithmDeleteFunc > > AlgorithmFactory
 
typedef AlgorithmFactory::value_type AlgorithmFactoryValueType
 
typedef std::map< std::string, std::pair< MobilityNewFunc, MobilityDeleteFunc > > MobilityFactory
 
typedef MobilityFactory::value_type MobilityFactoryValueType
 
typedef std::map< std::string, std::pair< OptimizerNewFunc, OptimizerDeleteFunc > > OptimizerFactory
 
typedef OptimizerFactory::value_type OptimizerFactoryValueType
 

Private Member Functions

void _setupCharacterData ()
 
void _updateCharacterPositions ()
 
template<typename X , typename X_ptr >
X_ptr checkCorbaServer (const std::string &n, CosNaming::NamingContext_var &cxt)
 CORBAサーバ取得 More...
 
bool defaultCheckCollision ()
 

Private Attributes

Algorithmalgorithm_
 使用する経路計画アルゴリズム More...
 
AlgorithmFactory algorithmFactory_
 経路計画アルゴリズムのファクトリ More...
 
std::string algorithmName_
 使用する経路計画アルゴリズム名 More...
 
OpenHRP::CharacterPositionSequence_var allCharacterPositions_
 
bool bboxMode_
 
std::vector< hrp::ColdetModelPaircheckPairs_
 
std::pair< std::string, std::string > collidingPair_
 
OpenHRP::CollisionDetector_var collisionDetector_
 
unsigned int countCollisionCheck_
 干渉チェック呼び出し回数 More...
 
ConfigurationSpace cspace_
 コンフィギュレーション空間 More...
 
CollisionDetectorcustomCollisionDetector_
 
bool debug_
 デバッグモード More...
 
double dt_
 デバッグモード時に使用する現在時刻 More...
 
applyConfigFunc m_applyConfigFunc
 
Mobilitymobility_
 使用する移動能力 More...
 
MobilityFactory mobilityFactory_
 移動能力のファクトリ More...
 
std::string mobilityName_
 使用する移動能力名 More...
 
hrp::BodyPtr model_
 経路計画の対象とするロボット More...
 
OpenHRP::ModelLoader_var modelLoader_
 ModelLoader への参照 More...
 
OpenHRP::OnlineViewer_var onlineViewer_
 デバッグモード時に使用する OnlineViewer への参照 More...
 
OptimizerFactory optimizerFactory_
 経路最適化アルゴリズムのファクトリ More...
 
CORBA::ORB_var orb_
 
std::vector< Configurationpath_
 経路 More...
 
std::vector< hrp::Vector3pointCloud_
 
double radius_
 radius of spheres assigned to points More...
 
TimeMeasure timeCollisionCheck_
 干渉チェックに使用したクロック数 More...
 
TimeMeasure timeForwardKinematics_
 
WorldPtr world_
 

Detailed Description

計画経路エンジン

経路計画を行うプログラムはこのクラスを使用する。干渉検出などを簡易化したメソッドを持つ。

Definition at line 44 of file hrplib/hrpPlanner/PathPlanner.h.

Member Typedef Documentation

◆ AlgorithmFactory

typedef std::map<const std::string, std::pair<AlgorithmNewFunc, AlgorithmDeleteFunc> > PathEngine::PathPlanner::AlgorithmFactory
private

Definition at line 48 of file hrplib/hrpPlanner/PathPlanner.h.

◆ AlgorithmFactoryValueType

typedef AlgorithmFactory::value_type PathEngine::PathPlanner::AlgorithmFactoryValueType
private

Definition at line 49 of file hrplib/hrpPlanner/PathPlanner.h.

◆ MobilityFactory

typedef std::map<std::string, std::pair<MobilityNewFunc, MobilityDeleteFunc> > PathEngine::PathPlanner::MobilityFactory
private

Definition at line 55 of file hrplib/hrpPlanner/PathPlanner.h.

◆ MobilityFactoryValueType

typedef MobilityFactory::value_type PathEngine::PathPlanner::MobilityFactoryValueType
private

Definition at line 56 of file hrplib/hrpPlanner/PathPlanner.h.

◆ OptimizerFactory

typedef std::map<std::string, std::pair<OptimizerNewFunc, OptimizerDeleteFunc> > PathEngine::PathPlanner::OptimizerFactory
private

Definition at line 62 of file hrplib/hrpPlanner/PathPlanner.h.

◆ OptimizerFactoryValueType

typedef OptimizerFactory::value_type PathEngine::PathPlanner::OptimizerFactoryValueType
private

Definition at line 63 of file hrplib/hrpPlanner/PathPlanner.h.

Constructor & Destructor Documentation

◆ PathPlanner()

PathPlanner::PathPlanner ( unsigned int  dim,
WorldPtr  world = WorldPtr(),
bool  isDebugMode = false 
)

コンストラクタ

Parameters
dimコンフィギュレーション空間の次元
world物理世界
isDebugModeデバッグモードにするか否か

Definition at line 82 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ ~PathPlanner()

PathPlanner::~PathPlanner ( )

デストラクタ

Definition at line 123 of file hrplib/hrpPlanner/PathPlanner.cpp.

Member Function Documentation

◆ _setupCharacterData()

void PathPlanner::_setupCharacterData ( )
private

Definition at line 802 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ _updateCharacterPositions()

void PathPlanner::_updateCharacterPositions ( )
private

Definition at line 831 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ boundingBoxMode()

void PathEngine::PathPlanner::boundingBoxMode ( bool  mode)
inline

Definition at line 465 of file hrplib/hrpPlanner/PathPlanner.h.

◆ calcPath()

bool PathPlanner::calcPath ( )

経路計画を行う

Returns
計画が正常に終了した場合true、それ以外はfalseを返す

Definition at line 737 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ checkCollision() [1/3]

bool PathPlanner::checkCollision ( )

現在の状態で干渉検出を行う

Returns
干渉している場合true, それ以外false

Definition at line 623 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ checkCollision() [2/3]

bool PathPlanner::checkCollision ( const Configuration pos)

干渉検出を行う

Parameters
posロボットの位置
Returns
干渉している場合true, それ以外false

Definition at line 580 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ checkCollision() [3/3]

bool PathPlanner::checkCollision ( const std::vector< Configuration > &  path)

パスの干渉検出を行う

Parameters
pathパス
Returns
一点でも干渉しているとtrue。ただし視点と終点はチェックしない

Definition at line 706 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ checkCorbaServer()

template<typename X , typename X_ptr >
X_ptr PathPlanner::checkCorbaServer ( const std::string &  n,
CosNaming::NamingContext_var &  cxt 
)
private

CORBAサーバ取得

CORBAサーバをネームサーバから取得する

Parameters
nサーバ名
cxtネーミングコンテキスト

Definition at line 31 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ collidingPair()

const std::pair<std::string, std::string>& PathEngine::PathPlanner::collidingPair ( )
inline

Definition at line 467 of file hrplib/hrpPlanner/PathPlanner.h.

◆ countCollisionCheck()

unsigned int PathEngine::PathPlanner::countCollisionCheck ( ) const
inline

干渉チェックを呼び出した回数を取得する

Returns
干渉チェックを呼び出した回数

Definition at line 455 of file hrplib/hrpPlanner/PathPlanner.h.

◆ defaultCheckCollision()

bool PathPlanner::defaultCheckCollision ( )
private

Definition at line 639 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ getAlgorithm()

Algorithm* PathEngine::PathPlanner::getAlgorithm ( )
inline

計画アルゴリズムを取得する

Returns
計画アルゴリズム

Definition at line 411 of file hrplib/hrpPlanner/PathPlanner.h.

◆ getAlgorithmNames()

void PathPlanner::getAlgorithmNames ( std::vector< std::string > &  algorithms)

経路計画アルゴリズム名の一覧を取得する

Returns
経路計画アルゴリズム名文字列の配列

Definition at line 157 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ getConfigurationSpace()

ConfigurationSpace* PathEngine::PathPlanner::getConfigurationSpace ( )
inline

コンフィギュレーション空間設定を取得する

Returns
コンフィギュレーション空間設定

Definition at line 417 of file hrplib/hrpPlanner/PathPlanner.h.

◆ getMobility()

Mobility* PathEngine::PathPlanner::getMobility ( )
inline

移動能力を取得する

Returns
移動能力

Definition at line 405 of file hrplib/hrpPlanner/PathPlanner.h.

◆ getMobilityNames()

void PathPlanner::getMobilityNames ( std::vector< std::string > &  mobilitys)

移動能力名の一覧を取得する

Returns
移動能力名の配列

Definition at line 145 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ getOptimizerNames()

void PathPlanner::getOptimizerNames ( std::vector< std::string > &  optimizers)

経路最適化アルゴリズム名の一覧を取得する

Returns
経路最適化アルゴリズム名文字列の配列

Definition at line 136 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ getPath()

std::vector< Configuration > PathPlanner::getPath ( )

計画された経路の補間されたものを取得する

Returns
補間された経路

Definition at line 787 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ getProperties()

bool PathPlanner::getProperties ( const std::string &  algorithm,
std::vector< std::string > &  names,
std::vector< std::string > &  values 
)

経路計画アルゴリズムのプロパティ名一覧を取得する

Parameters
algorithm経路計画アルゴリズムの名称
namesプロパティ名文字列の配列
valuesプロパティ値文字列の配列
Returns
取得に成功した場合true、指定したアルゴリズムが見つからなかった場合falseを返す

Definition at line 169 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ getRoadmap()

RoadmapPtr PathEngine::PathPlanner::getRoadmap ( )
inline

ロードマップを取得する

Returns
ロードマップ

Definition at line 387 of file hrplib/hrpPlanner/PathPlanner.h.

◆ getWayPoints()

std::vector< Configuration > & PathPlanner::getWayPoints ( )

計画された経路を取得する

Returns
計画された経路

Definition at line 783 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ getWorldState()

void PathPlanner::getWorldState ( OpenHRP::WorldState_out  wstate)

物理世界の状況を取得する

Parameters
wstate物理世界の状況

Definition at line 605 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ initPlanner()

void PathPlanner::initPlanner ( const std::string &  nameServer)

初期化。NameServer, ModelLoaderとの接続を行う。

Parameters
nameServerCORBAネームサーバの位置をホスト名:ポート番号の形式で指定る。

Definition at line 191 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ initSimulation()

void PathPlanner::initSimulation ( )

動力学シミュレータを初期化する

Definition at line 555 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ optimize()

bool PathPlanner::optimize ( const std::string &  optimizer)

指定した方法で経路を最適化する

Parameters
optimizer最適化法の名称
Returns
指定した最適化法が見つからなかった場合false、それ以外true

Definition at line 771 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ registerAlgorithm()

void PathPlanner::registerAlgorithm ( const std::string &  algorithmName,
AlgorithmNewFunc  newFunc,
AlgorithmDeleteFunc  deleteFunc 
)

経路計画アルゴリズムの登録

Parameters
algorithmName経路計画アルゴリズム名
newFunc
deleteFunc

Definition at line 696 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ registerCharacter() [1/2]

BodyPtr PathPlanner::registerCharacter ( const char *  name,
OpenHRP::BodyInfo_ptr  cInfo 
)

キャラクタを動力学シミュレータに登録する。

Parameters
nameモデル名
cInfoモデルデータ

Definition at line 411 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ registerCharacter() [2/2]

BodyPtr PathPlanner::registerCharacter ( const char *  name,
hrp::BodyPtr  i_body 
)

キャラクタを動力学シミュレータに登録する。

Parameters
nameモデル名
i_bodyモデルデータ

Definition at line 437 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ registerCharacterByURL()

BodyPtr PathPlanner::registerCharacterByURL ( const char *  name,
const char *  url 
)

キャラクタを動力学シミュレータに登録する。

Parameters
nameモデル名
urlモデルURL

Definition at line 292 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ registerIntersectionCheckPair()

void PathPlanner::registerIntersectionCheckPair ( const char *  char1,
const char *  name1,
const char *  char2,
const char *  name2,
CORBA::Double  tolerance 
)

衝突検出ペアを設定する

Parameters
char1キャラクタ1
name1キャラクタ1のリンク
char2キャラクタ2
name2キャラクタ2のリンク
toleranceリンク間の距離がこの値以下になると干渉と見なされる

Definition at line 490 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ registerMobility()

void PathPlanner::registerMobility ( const std::string &  mobilityName,
MobilityNewFunc  newFunc,
MobilityDeleteFunc  deleteFunc 
)

移動能力の登録

Parameters
mobilityName移動能力名
newFunc
deleteFunc

Definition at line 700 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ registerOptimizer()

void PathPlanner::registerOptimizer ( const std::string &  optimizerName,
OptimizerNewFunc  newFunc,
OptimizerDeleteFunc  deleteFunc 
)

経路最適化アルゴリズムの登録

Parameters
optimizerName経路最適化アルゴリズム名
newFunc
deleteFunc

Definition at line 703 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ robot()

BodyPtr PathPlanner::robot ( )

ロボットを取得する

Returns
ロボット

Definition at line 881 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ setAlgorithmName()

void PathPlanner::setAlgorithmName ( const std::string &  algorithm)

使用する経路計画アルゴリズム名を指定する

Parameters
algorithm経路計画アルゴリズム名

Definition at line 274 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ setApplyConfigFunc()

void PathPlanner::setApplyConfigFunc ( applyConfigFunc  i_func)

コンフィギュレーションベクトルからロボットの姿勢をセットする関数をセットする

Parameters
i_funcコンフィギュレーションベクトルからロボットの姿勢をセットする関数

Definition at line 876 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ setCharacterPosition()

void PathPlanner::setCharacterPosition ( const char *  character,
const OpenHRP::DblSequence &  pos 
)

位置を設定する

Parameters
characterキャラクタ名
pos位置姿勢

Definition at line 317 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ setCollisionDetector()

void PathEngine::PathPlanner::setCollisionDetector ( CollisionDetector i_cd)
inline

Definition at line 469 of file hrplib/hrpPlanner/PathPlanner.h.

◆ setConfiguration()

bool PathPlanner::setConfiguration ( const Configuration pos)

コンフィギュレーションをセットする

Parameters
posコンフィギュレーション

Definition at line 575 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ setDebug()

void PathEngine::PathPlanner::setDebug ( bool  debug)
inline

デバッグモードの変更

Parameters
debugデバッグモードのOn/Off

Definition at line 442 of file hrplib/hrpPlanner/PathPlanner.h.

◆ setGoalConfiguration()

void PathEngine::PathPlanner::setGoalConfiguration ( const Configuration pos)
inline

ゴール位置を設定する

Parameters
pos終了位置

Definition at line 370 of file hrplib/hrpPlanner/PathPlanner.h.

◆ setMobilityName()

bool PathPlanner::setMobilityName ( const std::string &  mobility)

使用する移動能力を設定する

Parameters
mobility移動能力名
Returns
指定された移動能力が登録されていない場合false、それ以外はtrue

Definition at line 465 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ setPointCloud()

void PathPlanner::setPointCloud ( const std::vector< hrp::Vector3 > &  i_cloud,
double  i_radius 
)

干渉チェック対象となるポイントクラウドを設定する

Parameters
i_cloudポイントクラウド
i_radiusポイントクラウドの各点に割り当てる球の半径

Definition at line 891 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ setProperties()

void PathEngine::PathPlanner::setProperties ( const std::map< std::string, std::string > &  properties)
inline

アルゴリズムに対して各種情報を設定する

Parameters
propertiesname-valueの組

Definition at line 359 of file hrplib/hrpPlanner/PathPlanner.h.

◆ setRobotName()

void PathPlanner::setRobotName ( const std::string &  model)

移動動作の設計対象にするモデルを設定する

Parameters
modelモデル名

Definition at line 450 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ setStartConfiguration()

void PathEngine::PathPlanner::setStartConfiguration ( const Configuration pos)
inline

スタート位置を設定する

Parameters
pos初期位置

Definition at line 364 of file hrplib/hrpPlanner/PathPlanner.h.

◆ stopPlanning()

void PathEngine::PathPlanner::stopPlanning ( )
inline

計算を中止する

Definition at line 381 of file hrplib/hrpPlanner/PathPlanner.h.

◆ timeCollisionCheck()

double PathPlanner::timeCollisionCheck ( ) const

干渉チェックに使用した時間[s]を取得する

Returns
干渉チェックに使用した時間[s]

Definition at line 866 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ timeForwardKinematics()

double PathPlanner::timeForwardKinematics ( ) const

Definition at line 871 of file hrplib/hrpPlanner/PathPlanner.cpp.

◆ world()

WorldPtr PathPlanner::world ( )

物理世界を取得する

Returns
物理世界

Definition at line 886 of file hrplib/hrpPlanner/PathPlanner.cpp.

Member Data Documentation

◆ algorithm_

Algorithm* PathEngine::PathPlanner::algorithm_
private

使用する経路計画アルゴリズム

Definition at line 87 of file hrplib/hrpPlanner/PathPlanner.h.

◆ algorithmFactory_

AlgorithmFactory PathEngine::PathPlanner::algorithmFactory_
private

経路計画アルゴリズムのファクトリ

Definition at line 53 of file hrplib/hrpPlanner/PathPlanner.h.

◆ algorithmName_

std::string PathEngine::PathPlanner::algorithmName_
private

使用する経路計画アルゴリズム名

Definition at line 82 of file hrplib/hrpPlanner/PathPlanner.h.

◆ allCharacterPositions_

OpenHRP::CharacterPositionSequence_var PathEngine::PathPlanner::allCharacterPositions_
private

Definition at line 149 of file hrplib/hrpPlanner/PathPlanner.h.

◆ bboxMode_

bool PathEngine::PathPlanner::bboxMode_
private

Definition at line 154 of file hrplib/hrpPlanner/PathPlanner.h.

◆ checkPairs_

std::vector<hrp::ColdetModelPair> PathEngine::PathPlanner::checkPairs_
private

Definition at line 156 of file hrplib/hrpPlanner/PathPlanner.h.

◆ collidingPair_

std::pair<std::string, std::string> PathEngine::PathPlanner::collidingPair_
private

Definition at line 161 of file hrplib/hrpPlanner/PathPlanner.h.

◆ collisionDetector_

OpenHRP::CollisionDetector_var PathEngine::PathPlanner::collisionDetector_
private

Definition at line 148 of file hrplib/hrpPlanner/PathPlanner.h.

◆ countCollisionCheck_

unsigned int PathEngine::PathPlanner::countCollisionCheck_
private

干渉チェック呼び出し回数

Definition at line 137 of file hrplib/hrpPlanner/PathPlanner.h.

◆ cspace_

ConfigurationSpace PathEngine::PathPlanner::cspace_
private

コンフィギュレーション空間

Definition at line 102 of file hrplib/hrpPlanner/PathPlanner.h.

◆ customCollisionDetector_

CollisionDetector* PathEngine::PathPlanner::customCollisionDetector_
private

Definition at line 163 of file hrplib/hrpPlanner/PathPlanner.h.

◆ debug_

bool PathEngine::PathPlanner::debug_
private

デバッグモード

Definition at line 112 of file hrplib/hrpPlanner/PathPlanner.h.

◆ dt_

double PathEngine::PathPlanner::dt_
private

デバッグモード時に使用する現在時刻

Definition at line 117 of file hrplib/hrpPlanner/PathPlanner.h.

◆ m_applyConfigFunc

applyConfigFunc PathEngine::PathPlanner::m_applyConfigFunc
private

Definition at line 47 of file hrplib/hrpPlanner/PathPlanner.h.

◆ mobility_

Mobility* PathEngine::PathPlanner::mobility_
private

使用する移動能力

Definition at line 97 of file hrplib/hrpPlanner/PathPlanner.h.

◆ mobilityFactory_

MobilityFactory PathEngine::PathPlanner::mobilityFactory_
private

移動能力のファクトリ

Definition at line 60 of file hrplib/hrpPlanner/PathPlanner.h.

◆ mobilityName_

std::string PathEngine::PathPlanner::mobilityName_
private

使用する移動能力名

Definition at line 92 of file hrplib/hrpPlanner/PathPlanner.h.

◆ model_

hrp::BodyPtr PathEngine::PathPlanner::model_
private

経路計画の対象とするロボット

Definition at line 107 of file hrplib/hrpPlanner/PathPlanner.h.

◆ modelLoader_

OpenHRP::ModelLoader_var PathEngine::PathPlanner::modelLoader_
private

ModelLoader への参照

Definition at line 72 of file hrplib/hrpPlanner/PathPlanner.h.

◆ onlineViewer_

OpenHRP::OnlineViewer_var PathEngine::PathPlanner::onlineViewer_
private

デバッグモード時に使用する OnlineViewer への参照

Definition at line 77 of file hrplib/hrpPlanner/PathPlanner.h.

◆ optimizerFactory_

OptimizerFactory PathEngine::PathPlanner::optimizerFactory_
private

経路最適化アルゴリズムのファクトリ

Definition at line 67 of file hrplib/hrpPlanner/PathPlanner.h.

◆ orb_

CORBA::ORB_var PathEngine::PathPlanner::orb_
private

Definition at line 144 of file hrplib/hrpPlanner/PathPlanner.h.

◆ path_

std::vector<Configuration> PathEngine::PathPlanner::path_
private

経路

Definition at line 132 of file hrplib/hrpPlanner/PathPlanner.h.

◆ pointCloud_

std::vector<hrp::Vector3> PathEngine::PathPlanner::pointCloud_
private

Definition at line 158 of file hrplib/hrpPlanner/PathPlanner.h.

◆ radius_

double PathEngine::PathPlanner::radius_
private

radius of spheres assigned to points

Definition at line 159 of file hrplib/hrpPlanner/PathPlanner.h.

◆ timeCollisionCheck_

TimeMeasure PathEngine::PathPlanner::timeCollisionCheck_
private

干渉チェックに使用したクロック数

Definition at line 142 of file hrplib/hrpPlanner/PathPlanner.h.

◆ timeForwardKinematics_

TimeMeasure PathEngine::PathPlanner::timeForwardKinematics_
private

Definition at line 142 of file hrplib/hrpPlanner/PathPlanner.h.

◆ world_

WorldPtr PathEngine::PathPlanner::world_
private

Definition at line 146 of file hrplib/hrpPlanner/PathPlanner.h.


The documentation for this class was generated from the following files:


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Thu Sep 8 2022 02:24:09