プランニングシーン(PlanningScene)の仕様¶
-
class
planning_scene
::
PlanningScene
¶ このクラスは、プランナーから見たワールドを管理します。環境形状、ロボット形状、および状態が格納されます。
Inherits from noncopyable, std::enable_shared_from_this< PlanningScene >
基準座標に対する処理
-
const std::string &
getPlanningFrame
() const¶ 計画が実行される基準座標を取得します。
-
const robot_state::Transforms &
getTransforms
() const¶ 既知の基準座標から計画で用いられる基準座標への変換を取得します。
-
const robot_state::Transforms &
getTransforms
()¶ 既知の基準座標から計画で用いられる基準座標への変換を取得します。このバリアントはconstでは無いため、現在の状態も更新します。
-
robot_state::Transforms &
getTransformsNonConst
()¶ 既知の基準座標から計画で用いられる基準座標への変換を取得します。
-
const Eigen::Isometry3d &
getFrameTransform
(const std::string &id) const¶ 基準座標IDに対応する変換を取得します。これは、IDがリンク名、接続された剛体のID、または干渉オブジェクトである場合に有効です。変換が使用できない場合はIDを返します。knowsFrameTransform()を使用して、この関数が成功するかどうかをテストできます。
-
const Eigen::Isometry3d &
getFrameTransform
(const std::string &id)¶ 基準座標IDに対応する変換を取得します。これは、IDがリンク名、接続された剛体のID、または干渉オブジェクトである場合に有効です。変換が使用できない場合はIDを返します。knowsFrameTransform()を使用して、この関数が成功するかどうかをテストできます。この関数はconstでないため、現在の変換も更新できます。
-
const Eigen::Isometry3d &
getFrameTransform
(robot_state::RobotState &state, const std::string &id) const¶ 基準座標IDに対応する変換を取得します。これは、IDがリンク名、接続された剛体のID、または干渉オブジェクトである場合に有効です。変換が使用できない場合はIDを返します。knowsFrameTransform()を使用して、この関数が成功するかどうかをテストできます。この関数は、stateのリンク座標も更新します。
-
const Eigen::Isometry3d &
getFrameTransform
(const robot_state::RobotState &state, const std::string &id) const¶ 基準座標IDに対応する変換を取得します。これは、IDがリンク名、接続された剛体のID、または干渉オブジェクトである場合に有効です。変換が使用できない場合はIDを返します。knowsFrameTransform()を使用して、この関数が成功するかどうかをテストできます。
-
bool
knowsFrameTransform
(const std::string &id) const¶ 基準座標IDへの変換が既知かどうかを確認します。これは、IDがリンク名、接続された剛体のID、または干渉オブジェクトである場合に有効です。
-
bool
knowsFrameTransform
(const robot_state::RobotState &state, const std::string &id) const¶ 基準座標IDへの変換が既知かどうかを確認します。これは、IDがリンク名、接続された剛体のID、または干渉オブジェクトである場合に有効です。
planning sceneの形状に対する処理
-
void
addCollisionDetector
(const collision_detection::CollisionDetectorAllocatorPtr &allocator)¶ 新しい干渉検出器を追加します。
干渉検出器のタイプは、CollisionDetectorAllocatorのサブクラスであるアロケーター(へのシェアードポインター)で指定されます。これは、組み合わせて使用できるCollisionWorld/CollisionRobotを指定します。
このタイプの干渉検出器が既に追加されている場合は登録しません。
PlanningSceneには、デフォルトでFCL干渉検出器が含まれています。このFCL干渉検出器は、exclusive = trueを指定してsetActiveCollisionDetector()を呼び出して削除しない限り、常に使用されます。
例:FCL干渉検出を追加する(通常は必要ありません)には、planning_scene->addCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create());を呼び出します。
-
void
setActiveCollisionDetector
(const collision_detection::CollisionDetectorAllocatorPtr &allocator, bool exclusive = false)¶ 使用する干渉検出器のタイプを設定します。 まだ追加されていない場合は、addCollisionDetector()を呼び出して追加します。
exclusiveがtrueの場合、他のすべての干渉検出器が削除され、この検出器のみが使用されます。
例:FCL干渉検出器を使用するには、planning_scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create());
-
bool
setActiveCollisionDetector
(const std::string &collision_detector_name)¶ 使用する干渉検出器のタイプを設定します。このタイプは、addCollisionDetector()で既に追加されている必要があります。
成功した場合はtrue、collision_detector_nameが以前にaddCollisionDetector()で追加された干渉検出器の名前でない場合はfalseを返します。
-
void
getCollisionDetectorNames
(std::vector<std::string> &names) const¶ 現在追加されている干渉検出器のタイプを取得します。これらは、setActiveCollisionDetector()に渡すことができるタイプです。
-
const collision_detection::WorldConstPtr &
getWorld
() const¶ ワールドの表現を取得します。
-
const collision_detection::CollisionWorldConstPtr &
getCollisionWorld
() const¶ ワールドのアクティブな干渉検出器を取得します。
-
const collision_detection::CollisionRobotConstPtr &
getCollisionRobot
() const¶ ロボットのアクティブな干渉検出器を取得します。
-
const collision_detection::CollisionRobotConstPtr &
getCollisionRobotUnpadded
() const¶ ロボットのアクティブな干渉検出器を取得します。
-
const collision_detection::CollisionWorldConstPtr &
getCollisionWorld
(const std::string &collision_detector_name) const¶ ワールドに特化した干渉検知器を取得します。見つからない場合は、アクティブなCollisionWorldを返します。
-
const collision_detection::CollisionRobotConstPtr &
getCollisionRobot
(const std::string &collision_detector_name) const¶ パディングされたロボット用の干渉検出器を取得します。見つからない場合は、アクティブなCollisionRobotを返します。
-
const collision_detection::CollisionRobotConstPtr &
getCollisionRobotUnpadded
(const std::string &collision_detector_name) const¶ パディングされていないロボット用の干渉検出器を取得します。見つからない場合は、アクティブなパッドなしのCollisionRobotを返します。
-
const collision_detection::CollisionRobotPtr &
getCollisionRobotNonConst
()¶ ロボットの干渉形状を取得します。これを使用して、アクティブなCollisionRobotのパディングとリンクスケールを設定できます。注:アクティブなロボットのパディングとスケールを変更した後、propogateRobotPadding()を呼び出して他のすべての干渉検出器にコピーする必要があります。
-
void
propogateRobotPadding
()¶ アクティブなCollisionRobotから他のCollisionRobotにスケールとパディングをコピーします。これは、アクティブなCollisionRobotのスケールまたはパディングに変更が加えられた後に呼び出す必要があります。これは、パディングのないCollisionRobotには影響しません。
-
const collision_detection::AllowedCollisionMatrix &
getAllowedCollisionMatrix
() const¶ 干渉行列(ACM)を取得します。
-
collision_detection::AllowedCollisionMatrix &
getAllowedCollisionMatrixNonConst
()¶ 干渉行列(ACM)を取得します。
planning sceneに対する干渉チェック
-
bool
isStateColliding
(const std::string &group = "", bool verbose = false)¶ 現在の状態が(環境または自己干渉と)干渉しているかどうかを確認します。グループ名が指定されている場合、干渉チェックはそのグループに対してのみ行われます。この関数はconstでないため、干渉チェックの前に現在の状態の座標変換が行われます。
-
bool
isStateColliding
(const std::string &group = "", bool verbose = false) const¶ 現在の状態が(環境または自己干渉と)干渉しているかどうかを確認します。グループ名が指定されている場合、干渉チェックはそのグループに対してのみ行われます。現在の座標変換は最新であることが期待されます。
-
bool
isStateColliding
(robot_state::RobotState &state, const std::string &group = "", bool verbose = false) const¶ stateが干渉しているかどうかを確認します(環境または自己干渉)。グループ名が指定されている場合、干渉チェックはそのグループに対してのみ行われます。干渉チェックの前にstateに対する座標変換が行われます。
-
bool
isStateColliding
(const robot_state::RobotState &state, const std::string &group = "", bool verbose = false) const¶ stateが干渉しているかどうかを確認します(環境または自己干渉)。グループ名が指定されている場合、干渉チェックはそのグループに対してのみ行われます。stateの座標変換は最新のものであることが期待されます。
-
bool
isStateColliding
(const moveit_msgs::RobotState &state, const std::string &group = "", bool verbose = false) const¶ stateが干渉しているかどうかを確認します(環境または自己干渉)。グループ名が指定されている場合、干渉チェックはそのグループに対してのみ行われます。
-
void
checkCollision
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)¶ 現在の状態が干渉しているかどうかを確認し、必要に応じて、計算の前に現在の状態の座標変換を更新します。
-
void
checkCollision
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res) const¶ 現在の状態が干渉しているかどうかを確認します。現在の状態は更新されることが期待されます。
-
void
checkCollision
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, robot_state::RobotState &robot_state) const¶ 指定された状態(robot_state)が干渉しているかどうかを確認します。このバリアントは、constではないRobotStateを使ってupdateCollisionBodyTransforms()を呼び出します。
-
void
checkCollision
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &robot_state) const¶ 指定された状態(robot_state)が干渉しているかどうかを確認します。 RobotStateの座標変換は最新のものであると期待されます。
-
void
checkCollision
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ 与えられた干渉行列(ACM)に関して、指定された状態(RobotState)が干渉しているかどうかを確認します。このバリアントは、constでないRobotStateを取り、必要に応じて座標変換を更新します。
-
void
checkCollision
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ 与えられた干渉行列(ACM)に関して、指定された状態(RobotState)が干渉しているかどうかを確認します。
-
void
checkCollisionUnpadded
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)¶ パディングのないcollision_detection::CollisionRobotインスタンスを使用して現在の状態が干渉しているかどうかを確認します。関数はconstでないため、必要に応じて現在の座標変換も更新されます。
-
void
checkCollisionUnpadded
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res) const¶ パディングのないcollision_detection::CollisionRobotインスタンスを使用して現在の状態が干渉しているかどうかを確認します。
-
void
checkCollisionUnpadded
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &robot_state) const¶ パディングのないcollision_detection::CollisionRobotインスタンスを使用して指定された状態(robot_state)が干渉しているかどうかを確認します。
-
void
checkCollisionUnpadded
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, robot_state::RobotState &robot_state) const¶ パディングのないcollision_detection::CollisionRobotインスタンスを使用して指定された状態(robot_state)が干渉しているかどうかを確認します。必要に応じて、robot_stateの座標変換を更新します。
-
void
checkCollisionUnpadded
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ パディングのないcollision_detection::CollisionRobotインスタンスを使用して、与えられた干渉行列(ACM)に関して、指定された状態(robot_state)が干渉しているかどうかを確認します。この関数のバリアントは、constでないrobot_stateを取り、必要に応じて座標変換を更新します。
-
void
checkCollisionUnpadded
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ パディングのないcollision_detection::CollisionRobotインスタンスを使用して、与えられた干渉行列(ACM)に関して、指定された状態(robot_state)が干渉しているかどうかを確認します。
-
void
checkSelfCollision
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)¶ 現在の状態が自己干渉になっているかどうかを確認します。
-
void
checkSelfCollision
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res) const¶ 現在の状態が自己干渉になっているかどうかを確認します。
-
void
checkSelfCollision
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, robot_state::RobotState &robot_state) const¶ 指定された状態(robot_state)が自己干渉しているかどうかを確認します。
-
void
checkSelfCollision
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &robot_state) const¶ 指定された状態(robot_state)が自己干渉しているかどうかを確認します。
-
void
checkSelfCollision
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ 与えられた干渉行列(ACM)に対して、指定された状態(robot_state)が自己干渉状態にあるかどうかを確認します。 robot_stateのリンク変換は、必要に応じて更新されます。
-
void
checkSelfCollision
(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ 与えられた干渉行列(ACM)に関して、指定された状態(robot_state)が自己干渉しているかどうかを確認します
-
void
getCollidingLinks
(std::vector<std::string> &links)¶ 現在のstateの干渉に関係しているリンクの名前を取得します。
-
void
getCollidingLinks
(std::vector<std::string> &links) const¶ 現在のstateの干渉に関係しているリンクの名前を取得します。
-
void
getCollidingLinks
(std::vector<std::string> &links, robot_state::RobotState &robot_state) const¶ robot_stateの干渉に関係するリンクの名前を取得します。必要に応じて、robot_stateの座標変換を更新します。
-
void
getCollidingLinks
(std::vector<std::string> &links, const robot_state::RobotState &robot_state) const¶ robot_stateの干渉に関係するリンクの名前を取得します。
-
void
getCollidingLinks
(std::vector<std::string> &links, robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ 許可された干渉行列(ACM)を指定して、状態robot_stateの干渉に関係するリンクの名前を取得します
-
void
getCollidingLinks
(std::vector<std::string> &links, const robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ 許可された干渉行列(ACM)を指定して、状態robot_stateの干渉に関係するリンクの名前を取得します
-
void
getCollidingPairs
(collision_detection::CollisionResult::ContactMap &contacts)¶ 現在の状態の干渉に関係しているリンクの名前を取得します。必要に応じて、現在の状態の座標変換を更新します。
-
void
getCollidingPairs
(collision_detection::CollisionResult::ContactMap &contacts) const¶ 現在のstateの干渉に関係しているリンクの名前を取得します。
-
void
getCollidingPairs
(collision_detection::CollisionResult::ContactMap &contacts, const robot_state::RobotState &robot_state) const¶ robot_stateの干渉に関係するリンクの名前を取得します。
-
void
getCollidingPairs
(collision_detection::CollisionResult::ContactMap &contacts, robot_state::RobotState &robot_state) const¶ robot_stateの干渉に関係するリンクの名前を取得します。必要に応じて、robot_stateの座標変換を更新します。
-
void
getCollidingPairs
(collision_detection::CollisionResult::ContactMap &contacts, robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ 許可された干渉行列(ACM)を指定して、robot_stateの干渉に関係するリンクの名前を取得します。必要に応じて、robot_stateの座標変換を更新します。
-
void
getCollidingPairs
(collision_detection::CollisionResult::ContactMap &contacts, const robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ 許可された干渉行列(ACM)を指定して、状態robot_stateの干渉に関係するリンクの名前を取得します
距離計算
-
double
distanceToCollision
(robot_state::RobotState &robot_state) const¶ 状態robot_stateのロボットモデルから最も近い干渉までの距離(自己干渉を無視)
-
double
distanceToCollision
(const robot_state::RobotState &robot_state) const¶ 状態robot_stateのロボットモデルから最も近い干渉までの距離(自己干渉を無視)
-
double
distanceToCollisionUnpadded
(robot_state::RobotState &robot_state) const¶ ロボットにパディングがない場合、状態robot_stateのロボットモデルから最も近い干渉までの距離(自己干渉を無視)。
-
double
distanceToCollisionUnpadded
(const robot_state::RobotState &robot_state) const¶ ロボットにパディングがない場合、状態robot_stateのロボットモデルから最も近い干渉までの距離(自己干渉を無視)。
-
double
distanceToCollision
(robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ 状態robot_stateのロボットモデルから最も近い干渉までの距離。自己干渉と干渉が許可されているオブジェクトを無視します。
-
double
distanceToCollision
(const robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ 状態robot_stateのロボットモデルから最も近い干渉までの距離。自己干渉と干渉が許可されているオブジェクトを無視します。
-
double
distanceToCollisionUnpadded
(robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ 状態robot_stateのロボットモデルから最も近い干渉までの距離。ロボットにパディングがない場合、自己干渉と干渉が許可されているオブジェクトは無視されます。
-
double
distanceToCollisionUnpadded
(const robot_state::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const¶ 状態robot_stateのロボットモデルから最も近い干渉までの距離。ロボットにパディングがない場合、自己干渉と干渉を許可されているオブジェクトを無視します。
パブリック関数
-
PlanningScene
(const robot_model::RobotModelConstPtr &robot_model, const collision_detection::WorldPtr &world = collision_detection::WorldPtr(new collision_detection::World()))¶ RobotModelを使用して構築します
URDFとSRDFを使用して構築します。 PlanningSceneのRobotModelは、URDFとSRDFを使用して作成されます。
-
const std::string &
getName
() const¶ planning sceneの名前を取得します。デフォルトでは空です。
-
void
setName
(const std::string &name)¶ planning sceneの名前を設定します。
-
PlanningScenePtr
diff
() const¶ これを親として使用する新しい子PlanningSceneを返します。
子シーンには、ワールドのコピーがあります。子ワールドに加えられた変更のリスト(world_diff_内)を格納します。
robot_model_、robot_state_、scene_transforms_、およびacm_はコピーされません。それらは親と共有されます。したがって、これらの変更が親で行われた場合、それらは子にも反映されます。ただし、これらのいずれかが子で変更された場合(get*NonConst関数が呼び出された場合)、コピーが行われ、親の後続の変更は子に反映されなくなります。
-
PlanningScenePtr
diff
(const moveit_msgs::PlanningScene &msg) const¶ このplanning sceneを親として使用し、msgで指定された差分を適用した新しい子PlanningSceneを生成します。
-
const PlanningSceneConstPtr &
getParent
() const¶ (差分の計算の対象になっている)親シーンを取得します。空の場合もあります。
-
const robot_model::RobotModelConstPtr &
getRobotModel
() const¶ planning sceneが関連付けられている運動学モデルを取得します。
-
const robot_state::RobotState &
getCurrentState
() const¶ ロボットの状態を取得します。
-
robot_state::RobotState &
getCurrentStateNonConst
()¶ ロボットの状態を取得します。
-
robot_state::RobotStatePtr
getCurrentStateUpdated
(const moveit_msgs::RobotState &update) const¶ 状態メッセージの更新によって上書きされた部分を含む現在の状態のコピーを取得します。
-
void
saveGeometryToStream
(std::ostream &out) const¶ planning sceneの形状情報をプレーンテキストとしてストリームに保存します。
-
bool
loadGeometryFromStream
(std::istream &in)¶ ストリームからplanning sceneの形状情報を読み込みます。
-
bool
loadGeometryFromStream
(std::istream &in, const Eigen::Isometry3d &offset)¶ オフセットを適用しながらストリームからplanning sceneの形状情報を読み込みます。
-
void
getPlanningSceneDiffMsg
(moveit_msgs::PlanningScene &scene) const¶ このPlanningSceneインスタンスと親の差分をメッセージシーンに入力します。親がない場合は、すべてが差分であると見なされ、関数はgetPlanningSceneMsg()と同様に動作します
-
void
getPlanningSceneMsg
(moveit_msgs::PlanningScene &scene) const¶ setPlanningSceneMsg()を使用してシーンを後で完全に再構築できるように、必要なすべてのデータを含むメッセージを作成します
-
void
getPlanningSceneMsg
(moveit_msgs::PlanningScene &scene, const moveit_msgs::PlanningSceneComponents &comp) const¶ compで要求されたデータを使用してメッセージを作成します。 compで全てのデータが指定された場合、これは完全なplanning sceneメッセージになります。
-
bool
getCollisionObjectMsg
(moveit_msgs::CollisionObject &collision_obj, const std::string &ns) const¶ 指定されたオブジェクトの干渉オブジェクトデータでメッセージ(collision_object)を構築します。
-
void
getCollisionObjectMsgs
(std::vector<moveit_msgs::CollisionObject> &collision_objs) const¶ planning_scene内のすべてのオブジェクトの干渉オブジェクトデータを使用して、メッセージのリスト(collision_objects)を構築します。
-
bool
getAttachedCollisionObjectMsg
(moveit_msgs::AttachedCollisionObject &attached_collision_obj, const std::string &ns) const¶ 指定された接続されたオブジェクトの干渉オブジェクトデータを使用して、メッセージ(attached_collision_object)を作成します。
-
void
getAttachedCollisionObjectMsgs
(std::vector<moveit_msgs::AttachedCollisionObject> &attached_collision_objs) const¶ planning_scene内のすべての接続されたオブジェクトの干渉オブジェクトデータを使用して、メッセージのリスト(attached_collision_objects)を作成します。
-
bool
getOctomapMsg
(octomap_msgs::OctomapWithPose &octomap) const¶ planning_sceneのoctomapデータを使用してメッセージ(octomap)を作成します。
-
void
getObjectColorMsgs
(std::vector<moveit_msgs::ObjectColor> &object_colors) const¶ planning_sceneのオブジェクトの色を使って、メッセージのリスト(object_colors)を作成します。
-
bool
setPlanningSceneDiffMsg
(const moveit_msgs::PlanningScene &scene)¶ メッセージが差分(is_diff)としてマークされていない場合でも、このplanning sceneに変更を差分として適用します。親は存在する必要はありません。ただし、プランニングインスタンスの既存のデータはクリアされません。メッセージのデータは追加されるのみです(たとえば、ロボットの状態などの場合は上書きされます)。
-
bool
setPlanningSceneMsg
(const moveit_msgs::PlanningScene &scene)¶ メッセージが差分(is_diff)としてマークされている場合でも、このインスタンスをシーンメッセージで単一にシリアル化されたものと同様に設定します。
-
bool
usePlanningSceneMsg
(const moveit_msgs::PlanningScene &scene)¶ メッセージのis_diffの設定に応じて、setPlanningSceneMsg()またはsetPlanningSceneDiffMsg()を呼び出します。
-
void
removeAllCollisionObjects
()¶ planning sceneのすべての干渉オブジェクトをクリアします。
-
void
setCurrentState
(const moveit_msgs::RobotState &state)¶ 現在のロボットの状態をstateに設定します。すべての関節値が指定されていない場合、以前に保存されていた関節値が保持されます。
-
void
setCurrentState
(const robot_state::RobotState &state)¶ 現在のロボットの状態を設定します。
-
void
setAttachedBodyUpdateCallback
(const robot_state::AttachedBodyCallback &callback)¶ 現在のシーンの状態に変更が加えられたときにトリガーされるコールバックを設定します。
-
void
setCollisionObjectUpdateCallback
(const collision_detection::World::ObserverCallbackFn &callback)¶ 現在のシーンに変更が加えられたときにトリガーされるコールバックを設定します。
-
void
clearDiffs
()¶ 親に関して、この計画シーンで蓄積された差分をクリアします。親が指定されていない場合、この関数は何もしません。
-
void
pushDiffs
(const PlanningScenePtr &scene)¶ このシーンに親がある場合、その親に関する差分を、指定されたplanning scene(そのシーンが何であれ)に適用します。親が指定されていない場合、この関数は何もしません。
-
void
decoupleParent
()¶ このシーンで保持されている全てのデータをローカルで保持するようにします。変更されていないデータはすべて親からコピーされ、親へのポインターが破棄されます。
-
void
setStateFeasibilityPredicate
(const StateFeasibilityFn &fn)¶ 干渉チェックや制約評価でカバーされる以外の尺度で、状態の有効性を評価する関数を設定します。これは、問題固有の制約(安定性など)を設定するのに役立ちます
-
const StateFeasibilityFn &
getStateFeasibilityPredicate
() const¶ 干渉チェックや制約評価でカバーされる以外の尺度で、状態の有効性を評価する関数を取得します。
-
void
setMotionFeasibilityPredicate
(const MotionFeasibilityFn &fn)¶ 干渉チェックや制約評価でカバーされる以外の尺度で、モーションセグメントの有効性を評価する関数を設定します。
-
const MotionFeasibilityFn &
getMotionFeasibilityPredicate
() const¶ 干渉チェックや制約評価でカバーされる以外の尺度で、モーションセグメントの有効性を評価する関数を取得します。
-
bool
isStateFeasible
(const moveit_msgs::RobotState &state, bool verbose = false) const¶ setStateFeasibilityPredicate()で指定された評価関数に従って、指定された状態が実行可能かどうかを確認します。実行可能条件が指定されていない場合はtrueを返します。
-
bool
isStateFeasible
(const robot_state::RobotState &state, bool verbose = false) const¶ setStateFeasibilityPredicate()で指定された評価関数に従って、指定された状態が実行可能かどうかを確認します。実行可能条件が指定されていない場合はtrueを返します。
-
bool
isStateConstrained
(const moveit_msgs::RobotState &state, const moveit_msgs::Constraints &constr, bool verbose = false) const¶ 指定された状態が一連の制約を満たすかどうか確認します。
-
bool
isStateConstrained
(const robot_state::RobotState &state, const moveit_msgs::Constraints &constr, bool verbose = false) const¶ 指定された状態が一連の制約を満たすかどうか確認します。
-
bool
isStateConstrained
(const moveit_msgs::RobotState &state, const kinematic_constraints::KinematicConstraintSet &constr, bool verbose = false) const¶ 指定された状態が一連の制約を満たすかどうか確認します。
-
bool
isStateConstrained
(const robot_state::RobotState &state, const kinematic_constraints::KinematicConstraintSet &constr, bool verbose = false) const¶ 指定された状態が一連の制約を満たすかどうか確認します。
-
bool
isStateValid
(const moveit_msgs::RobotState &state, const std::string &group = "", bool verbose = false) const¶ 指定された状態が有効かどうかを確認します。これは、干渉と実行可能性チェックの実施を意味します。
-
bool
isStateValid
(const robot_state::RobotState &state, const std::string &group = "", bool verbose = false) const¶ 指定された状態が有効かどうかを確認します。これは、干渉と実行可能性チェックの実施を意味します。
-
bool
isStateValid
(const moveit_msgs::RobotState &state, const moveit_msgs::Constraints &constr, const std::string &group = "", bool verbose = false) const¶ 指定された状態が有効かどうかを確認します。これは、干渉、実行可能性、およびユーザー指定の有効条件が同時に成り立つかどうかをチェックすることを意味します。
-
bool
isStateValid
(const robot_state::RobotState &state, const moveit_msgs::Constraints &constr, const std::string &group = "", bool verbose = false) const¶ 指定された状態が有効かどうかを確認します。これは、干渉、実行可能性、およびユーザー指定の有効条件が同時に成り立つかどうかをチェックすることを意味します。
-
bool
isStateValid
(const robot_state::RobotState &state, const kinematic_constraints::KinematicConstraintSet &constr, const std::string &group = "", bool verbose = false) const¶ 指定された状態が有効かどうかを確認します。これは、干渉、実行可能性、およびユーザー指定の有効条件が同時に成り立つかどうかをチェックすることを意味します。
-
bool
isPathValid
(const moveit_msgs::RobotState &start_state, const moveit_msgs::RobotTrajectory &trajectory, const std::string &group = "", bool verbose = false, std::vector<std::size_t> *invalid_index = NULL) const¶ 指定されたパスが有効かどうかを確認します。各状態の有効性がチェックされます(干渉回避と実現可能性)
-
bool
isPathValid
(const moveit_msgs::RobotState &start_state, const moveit_msgs::RobotTrajectory &trajectory, const moveit_msgs::Constraints &path_constraints, const std::string &group = "", bool verbose = false, std::vector<std::size_t> *invalid_index = NULL) const¶ 指定されたパスが有効かどうかを確認します。各状態の妥当性(干渉回避、実現可能性、制約充足)がチェックされます。また、通過した軌跡の最後の状態によってゴール制約が満たされていることも確認されます。
-
bool
isPathValid
(const moveit_msgs::RobotState &start_state, const moveit_msgs::RobotTrajectory &trajectory, const moveit_msgs::Constraints &path_constraints, const moveit_msgs::Constraints &goal_constraints, const std::string &group = "", bool verbose = false, std::vector<std::size_t> *invalid_index = NULL) const¶ 指定されたパスが有効かどうかを確認します。各状態の妥当性(干渉回避、実現可能性、制約充足)がチェックされます。また、通過した軌跡の最後の状態によってゴール制約が満たされていることも確認されます。
-
bool
isPathValid
(const moveit_msgs::RobotState &start_state, const moveit_msgs::RobotTrajectory &trajectory, const moveit_msgs::Constraints &path_constraints, const std::vector<moveit_msgs::Constraints> &goal_constraints, const std::string &group = "", bool verbose = false, std::vector<std::size_t> *invalid_index = NULL) const¶ 指定されたパスが有効かどうかを確認します。各状態の妥当性(干渉回避、実現可能性、制約充足)がチェックされます。また、通過した軌跡の最後の状態によってゴール制約が満たされていることも確認されます。
-
bool
isPathValid
(const robot_trajectory::RobotTrajectory &trajectory, const moveit_msgs::Constraints &path_constraints, const std::vector<moveit_msgs::Constraints> &goal_constraints, const std::string &group = "", bool verbose = false, std::vector<std::size_t> *invalid_index = NULL) const¶ 指定されたパスが有効かどうかを確認します。各状態の妥当性(干渉回避、実現可能性、制約充足)がチェックされます。また、通過した軌跡の最後の状態によってゴール制約が満たされていることも確認されます。
-
bool
isPathValid
(const robot_trajectory::RobotTrajectory &trajectory, const moveit_msgs::Constraints &path_constraints, const moveit_msgs::Constraints &goal_constraints, const std::string &group = "", bool verbose = false, std::vector<std::size_t> *invalid_index = NULL) const¶ 指定されたパスが有効かどうかを確認します。各状態の妥当性(干渉回避、実現可能性、制約充足)がチェックされます。また、通過した軌跡の最後の状態によってゴール制約が満たされていることも確認されます。
-
bool
isPathValid
(const robot_trajectory::RobotTrajectory &trajectory, const moveit_msgs::Constraints &path_constraints, const std::string &group = "", bool verbose = false, std::vector<std::size_t> *invalid_index = NULL) const¶ 指定されたパスが有効かどうかを確認します。各状態の妥当性(干渉回避、実現可能性、制約充足)がチェックされます。
-
bool
isPathValid
(const robot_trajectory::RobotTrajectory &trajectory, const std::string &group = "", bool verbose = false, std::vector<std::size_t> *invalid_index = NULL) const¶ 指定されたパスが有効かどうかを確認します。各状態の有効性がチェックされます(干渉回避と実現可能性)
-
void
getCostSources
(const robot_trajectory::RobotTrajectory &trajectory, std::size_t max_costs, std::set<collision_detection::CostSource> &costs, double overlap_fraction = 0.9) const¶ 指定された軌道の上位max_costs個のコストソースを取得します。結果はcostsに保存されます。
-
void
getCostSources
(const robot_trajectory::RobotTrajectory &trajectory, std::size_t max_costs, const std::string &group_name, std::set<collision_detection::CostSource> &costs, double overlap_fraction = 0.9) const¶ グループgroup_nameについてのみ、指定された軌道の上位max_costs個のコストソースを取得します。結果はcostsに保存されます。
-
void
getCostSources
(const robot_state::RobotState &state, std::size_t max_costs, std::set<collision_detection::CostSource> &costs) const¶ 指定した状態の上位のmax_costs個のコストソースを取得します。結果はcostsに保存されます。
-
void
getCostSources
(const robot_state::RobotState &state, std::size_t max_costs, const std::string &group_name, std::set<collision_detection::CostSource> &costs) const¶ グループgroup_nameについてのみ、指定された軌道の上位max_costs個のコストソースを取得します。結果はcostsに保存されます。
-
void
printKnownObjects
(std::ostream &out = std::cout) const¶ planning sceneの内容に関するデバッグ情報を出力します。
パブリック静的関数
-
bool
isEmpty
(const moveit_msgs::PlanningScene &msg)¶ メッセージにplanning sceneに関する情報が含まれているか、それが単なるデフォルトの空のメッセージであるかを確認します。
-
bool
isEmpty
(const moveit_msgs::PlanningSceneWorld &msg)¶ メッセージにplanning sceneのワールドに関する情報が含まれているか、それが単なるデフォルトの空のメッセージであるかを確認します。
-
bool
isEmpty
(const moveit_msgs::RobotState &msg)¶ メッセージにロボットの状態に関する情報が含まれているか、それが単なるデフォルトの空のメッセージであるかを確認します。
-
PlanningScenePtr
clone
(const PlanningSceneConstPtr &scene)¶ planning sceneを複製します。シーンシーンが親に依存している場合は、クローンシーンは依存しないように複製されます。
-
const std::string &
-
class
planning_scene_monitor
::
PlanningSceneMonitor
¶ PlanningSceneMonitorは、ROSのplanning_sceneトピックにサブスクライブし最新のシーン情報を保持します。
Inherits from noncopyable
パブリック関数
コンストラクタ
- パラメータ
robot_description:URDFを含むROSパラメーターの名前(文字列形式)
tf_buffer:tf2_ros::Bufferへのポインタ
name:このplanning sceneモニターを識別する名前
コンストラクタ
- パラメータ
rml:キネマティックモデルローダーへのポインタ
tf_buffer:tf2_ros::Bufferへのポインタ
name:このplanning sceneモニターを識別する名前
コンストラクタ
- パラメータ
scene: モニタした情報を使って最新の状態を保持しているシーンインスタンス
robot_description:URDFを含むROSパラメーターの名前(文字列形式)
tf_buffer:tf2_ros::Bufferへのポインタ
name:このplanning sceneモニターを識別する名前
コンストラクタ
- パラメータ
scene: モニタした情報を使って最新の状態を保持しているシーンインスタンス
rml:キネマティックモデルローダーへのポインタ
tf_buffer:tf2_ros::Bufferへのポインタ
name:このplanning sceneモニターを識別する名前
コンストラクタ
- パラメータ
scene: モニタした情報を使って最新の状態を保持しているシーンインスタンス
rml:キネマティックモデルローダーへのポインタ
nh: 外部の親NodeHandleモニターは、更新にこのNodeHandleのCallbackQueueを使用します。通常、これはグローバルキューとは異なるキューである必要があります。そうでない場合、タイムアウトが発生する可能性があります。
tf_buffer:tf2_ros::Bufferへのポインタ
name:このplanning sceneモニターを識別する名前
-
const std::string &
getName
() const¶ このモニターの名前を取得します。
-
const robot_model_loader::RobotModelLoaderPtr &
getRobotModelLoader
() const¶ キネマティックモデルローダーを取得します。
-
const planning_scene::PlanningScenePtr &
getPlanningScene
()¶ この機能の使用は避けてください!現在のplanning sceneへの安全でないポインターを返します。
- 警告
特殊な場合を除いて、この関数を直接呼び出しは避けてください。 PlanningSceneMonitorには、内部のPlanningSceneインスタンスのさまざまなコンテンツを更新および上書きするバックグラウンドスレッドがあります。この関数は、その動的内部オブジェクトへのポインタを返します。この関数の代わりに、LockedPlanningSceneROまたはLockedPlanningSceneRWの使用を推奨します。これにより、PlanningSceneMonitorがロックされ、PlanningSceneオブジェクトへの安全なアクセスが保障されます。
- 参照
LockedPlanningSceneRO
- 参照
LockedPlanningSceneRW。
- 戻り値
現在のplanning sceneへのポインター。
-
const planning_scene::PlanningSceneConstPtr &
getPlanningScene
() const¶ この機能の使用は避けてください!現在のplanning sceneへの安全でないポインターを返します。
- 警告
特殊な場合を除いて、この関数を直接呼び出しは避けてください。 PlanningSceneMonitorには、内部のPlanningSceneインスタンスのさまざまなコンテンツを更新および上書きするバックグラウンドスレッドがあります。この関数は、その動的内部オブジェクトへのポインタを返します。この関数の代わりに、LockedPlanningSceneROまたはLockedPlanningSceneRWの使用を推奨します。これにより、PlanningSceneMonitorがロックされ、PlanningSceneオブジェクトへの安全なアクセスが保障されます。
- 参照
LockedPlanningSceneRO
- 参照
LockedPlanningSceneRW。
- 戻り値
現在のplanning sceneへのポインター。
-
bool
updatesScene
(const planning_scene::PlanningSceneConstPtr &scene) const¶ このモニタによってシーンsceneを直接または間接的に更新できる場合は、trueを返します。この関数は、シーンのポインタがこのモニタに保持されているものと同じ場合、またはシーンの親が保持されている場合にtrueを返します。
-
bool
updatesScene
(const planning_scene::PlanningScenePtr &scene) const¶ このモニタによってシーンsceneを直接または間接的に更新できる場合は、trueを返します。この関数は、シーンのポインタがこのモニタに保持されているものと同じ場合、またはシーンの親が保持されている場合にtrueを返します。
-
const std::string &
getRobotDescription
() const¶ 保存されたロボットの説明を取得します。
- 戻り値
格納されたロボットデータのインスタンス
-
double
getDefaultRobotPadding
() const¶ デフォルトのロボットのパディングを取得します。
-
double
getDefaultRobotScale
() const¶ デフォルトのロボットスケーリングを取得します。
-
double
getDefaultObjectPadding
() const¶ デフォルトのオブジェクトのパディングを取得します。
-
double
getDefaultAttachedObjectPadding
() const¶ デフォルトの接続されたパディングを取得します。
-
const std::shared_ptr<tf2_ros::Buffer> &
getTFClient
() const¶ このクラスのコンストラクタに渡されたTFクライアントのインスタンスを取得します。
-
void
monitorDiffs
(bool flag)¶ デフォルトでは、保持されたplanning sceneは差分については扱いません。フラグがtrueの場合、保持されているシーンは差分のカウントを開始します。planning sceneの将来の更新は差分として保存され、差分の形で取得できます。フラグをfalseに設定すると、デフォルトの動作が復元されます。差分の保存は、planning sceneを公開するときに自動的に有効になります。
-
void
startPublishingPlanningScene
(SceneUpdateType event, const std::string &planning_scene_topic = MONITORED_PLANNING_SCENE_TOPIC)¶ 保持されたplanning sceneのパブリッシュを開始します。最初に発信されるメッセージは、完全なplanning sceneです。その後、イベントビットマスクで指定された更新で差分が送信されます。UPDATE_SCENEの場合、シーン全体が送信されます。
-
void
stopPublishingPlanningScene
()¶ 保持されたplanning sceneの公開を停止します。
-
void
setPlanningScenePublishingFrequency
(double hz)¶ planning sceneがパブリッシュされる最大頻度を設定します。
-
double
getPlanningScenePublishingFrequency
() const¶ planning sceneがパブリッシュされる最大周波数(Hz)を取得します
-
const CurrentStateMonitorPtr &
getStateMonitor
() const¶ 現在の状態モニターのインスタンスを取得します。
- 戻り値
保存された現在の状態モニターのインスタンス
-
void
updateFrameTransforms
()¶ tfを使用して、キネマティックモデルの一部ではない座標を変換します。これらの座標の例は、「map」および「odom_combined」です。この関数は、座標変換を使用するデータが受信されると自動的に呼び出されます。この関数は、たとえばプランニング要求を開始する前にも手動で呼び出す必要があります。
-
void
startStateMonitor
(const std::string &joint_states_topic = DEFAULT_JOINT_STATES_TOPIC, const std::string &attached_objects_topic = DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC)¶ 現在の状態モニターを開始します。
- パラメータ
joint_states_topic: 関節状態をリッスンするトピック
attachment_objects_topic: 接続された干渉オブジェクトをリッスンするトピック
-
void
stopStateMonitor
()¶ 状態モニターを停止します。
-
void
updateSceneWithCurrentState
()¶ モニターした状態を使用してシーンを更新します。この関数は、現在の状態の更新を受信すると自動的に呼び出されます(startStateMonitor()が呼び出された場合)。ただし、更新は、setStateUpdateFrequency()によって設定される最大頻度に調整されます。
-
void
setStateUpdateFrequency
(double hz)¶ 指定された周波数(Hz)でモニターした状態を使用してシーンを更新します。この関数は、CurrentStateMonitorからの更新がより高い頻度で受信される場合にのみ効果があります。その際、更新がここで指定された最大更新頻度を超えないように調整されます。
- パラメータ
hz: 更新頻度。デフォルトでは10Hzです。
-
double
getStateUpdateFrequency
() const¶ planning sceneの現在の状態が更新される最大周波数(Hz)を取得します。
-
void
startSceneMonitor
(const std::string &scene_topic = DEFAULT_PLANNING_SCENE_TOPIC)¶ シーンモニターを起動します。
- パラメータ
scene_topic: planning sceneトピックの名前
-
bool
requestPlanningSceneState
(const std::string &service_name = DEFAULT_PLANNING_SCENE_SERVICE)¶ サービスコールを使用してplanning sceneの状態を要求します。
- パラメータ
service_name: planning sceneのリクエストに使用するサービス名。これは、moveit_msgs::GetPlanningScene型のサービスである必要があり、通常「/get_planning_scene」です。
-
void
stopSceneMonitor
()¶ シーンモニターを停止します。
-
void
startWorldGeometryMonitor
(const std::string &collision_objects_topic = DEFAULT_COLLISION_OBJECT_TOPIC, const std::string &planning_scene_world_topic = DEFAULT_PLANNING_SCENE_WORLD_TOPIC, const bool load_octomap_monitor = true)¶ OccupancyMapMonitorを起動して、次の情報をリッスンします。
干渉オブジェクトをワールドに追加/削除/更新するリクエスト
干渉マップ
Requests to attached/detach collision objects
- パラメータ
collision_objects_topic: 干渉オブジェクトをリッスンするトピック
planning_scene_world_topic: ワールドシーンジオメトリをリッスンするトピック
load_octomap_monitor: 必要に応じてoctomapモニターを無効にするフラグ
-
void
stopWorldGeometryMonitor
()¶ ワールドジオメトリモニターを停止します。
-
void
addUpdateCallback
(const boost::function<void(SceneUpdateType)> &fn)¶ シーンの更新が受信されたときに呼び出される関数を追加します。
-
void
clearUpdateCallbacks
()¶ シーンの更新を受信したときに呼び出される関数をクリアします。
-
void
getMonitoredTopics
(std::vector<std::string> &topics) const¶ モニターがリッスンしているトピック名を取得します。
-
const ros::Time &
getLastUpdateTime
() const¶ planning sceneに(いずれかのモニターによって)最後の更新が行われた時刻を返します
-
void
triggerSceneUpdateEvent
(SceneUpdateType update_type)¶ この関数は、planning sceneが変更されるたびに呼び出されます。
-
bool
waitForCurrentRobotState
(const ros::Time &t, double wait_time = 1.)¶ ロボットの状態が時間tよりも新しくなるのを待ちます。
アクティブな状態モニターがない場合、シーンの更新はありません。したがって、タイムアウトを指定して、それらの更新を待つことができます。デフォルトは1秒です。
-
void
lockSceneRead
()¶ 読み取りのためにシーンをロックします(複数のスレッドが読み取りのために同時にロックできます)
-
void
unlockSceneRead
()¶ 読み取りからシーンのロックを解除します(複数のスレッドが読み取りのために同時にロックできます)
-
void
lockSceneWrite
()¶ 書き込み用にシーンをロックします(1つのスレッドのみが書き込み用にロックでき、他のスレッドは読み取り用にロックできません)
-
void
unlockSceneWrite
()¶ 書き込みからシーンをロックします(1つのスレッドのみが書き込みのためにロックでき、他のスレッドは読み取りのためにロックできません)
パブリック静的属性
-
const std::string
DEFAULT_JOINT_STATES_TOPIC
= "joint_states"¶ 関節状態を受信するためにデフォルトで使用されるトピックの名前。
-
const std::string
DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
= "attached_collision_object"¶ アタッチされた干渉オブジェクトにデフォルトで使用されるトピックの名前。
-
const std::string
DEFAULT_COLLISION_OBJECT_TOPIC
= "collision_object"¶ ワールドで干渉オブジェクトを受信するためにデフォルトで使用されるトピックの名前。
-
const std::string
DEFAULT_PLANNING_SCENE_WORLD_TOPIC
= "planning_scene_world"¶ planning sceneに関するジオメトリ情報を受信するためにデフォルトで使用されるトピックの名前(ワールドジオメトリの完全な上書き)
-
const std::string
DEFAULT_PLANNING_SCENE_TOPIC
= "planning_scene"¶ 完全なplanning sceneまたはplanning sceneの差分を受信するためにデフォルトで使用されるトピックの名前。
-
const std::string
DEFAULT_PLANNING_SCENE_SERVICE
= "get_planning_scene"¶ 完全なplanning sceneの状態を要求するためにデフォルトで使用されるサービスの名前。
-
const std::string
MONITORED_PLANNING_SCENE_TOPIC
= "monitored_planning_scene"¶ モニター対象のplanning sceneを公開するためにデフォルトで使用されるトピックの名前(名前に「/」がないため、トピック名にはノード名が接頭辞として付けられます)