運動学計算アルゴリズム基底クラス(KinematicsBase)の仕様¶
クラス図¶
各運動学計算アルゴリズムは、KinematicsBaseを基底クラスとして実装されており、自由に切り替えて利用できます。
既存の運動学計算アルゴリズムを使うだけでなく、独自のアルゴリズムを実装することもできます。 MoveItでは、ROSのpluginlibの仕組みを使って独自アルゴリズムの既存システムへのプラグインを実現しています。 詳しい方法については、以下の外部ドキュメントを参照してください。
https://ros-planning.github.io/moveit_tutorials/doc/creating_moveit_plugins/plugin_tutorial.html
一般に運動学の計算に解析解を使ったアルゴリズムの方が、数値解を使ったアルゴリズム(KDLKinematicsPluginなど)よりも高速で安定した解が得られます。
すでにロボットの解析解が得られている場合、それをプラグインの形で実装することを推奨します。
単純な形のロボットであれば、IKFastを利用すると、解析解を自動で計算することもできます。
解析解が得られていないロボットについても、数値解を使ったアルゴリズム(KDLKinematicsPluginなど)とURDF形式のロボット構造データを組み合わせることで、逆運動学が計算できます。
基底クラス¶
KinematicsBase¶
-
class
kinematics
::
KinematicsBase
¶ 運動学ソルバーのインターフェイスを提供します。
Subclassed by _NAMESPACE_::IKFastKinematicsPlugin, kdl_kinematics_plugin::KDLKinematicsPlugin, lma_kinematics_plugin::LMAKinematicsPlugin, pr2_arm_kinematics::PR2ArmKinematicsPlugin, srv_kinematics_plugin::SrvKinematicsPlugin
パブリックタイプ
-
typedef boost::function<void(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)>
IKCallbackFn
¶ 逆運動学の解を検証するコールバック関数。通常、干渉チェックに使用されます。
パブリック関数
-
virtual bool
getPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, std::vector<double> &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const = 0¶ エンドエフェクタの位置姿勢を入力として、それに実現するための関節角度を計算します。
In contrast to the searchPositionIK methods, this one is expected to return the solution closest to the seed state. Randomly re-seeding is explicitly not allowed.
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
solution:解ベクトル
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
bool
getPositionIK
(const std::vector<geometry_msgs::Pose> &ik_poses, const std::vector<double> &ik_seed_state, std::vector<std::vector<double>> &solutions, KinematicsResult &result, const kinematics::KinematicsQueryOptions &options) const¶ 複数のエンドエフェクタの目的の位置姿勢を入力として、それに到達できる関節角度を計算します。
このデフォルトの実装では、1つの解のみを返すため、結果は、ゼロで初期化された初期姿勢でgetPositionIK関数を呼び出すことと同等です。
- 戻り値
有効な解のセットが見つかった場合はtrue、そうでない場合はfalse。
- パラメータ
ik_poses:各エンドエフェクタの位置姿勢
ik_seed_state:逆運動学計算の初期値
solutions:有効な関節角を格納したベクトルのベクトル
result:クエリの結果を格納する構造体
options:使用される冗長性の離散化のタイプ。デフォルトの実装では、KinematicSearches::NO_DISCRETIZATIONタイプのみがサポートされており、他のタイプを設定すると失敗します。
-
virtual bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, std::vector<double> &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const = 0¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
solution:解ベクトル
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
virtual bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, const std::vector<double> &consistency_limits, std::vector<double> &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const = 0¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
consistency_limits:ソリューション内の各関節が、与えられた初期状態の対応する関節から変化できる角度
solution:解ベクトル
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
virtual bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, std::vector<double> &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const = 0¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
solution:解ベクトル
solution_callback:逆運動学の解を検証するためのコールバック
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
virtual bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, const std::vector<double> &consistency_limits, std::vector<double> &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const = 0¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
consistency_limits:ソリューション内の各関節が、与えられた初期状態の対応する関節から変化できる角度
solution:解ベクトル
solution_callback:逆運動学の解を検証するためのコールバック
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
virtual bool
searchPositionIK
(const std::vector<geometry_msgs::Pose> &ik_poses, const std::vector<double> &ik_seed_state, double timeout, const std::vector<double> &consistency_limits, std::vector<double> &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions(), const moveit::core::RobotState *context_state = NULL) const¶ 複数のエンドエフェクタを持つプランニンググループに必要な一連の位置姿勢が与えられたら、それらに到達するために必要な関節角度を検索します。これは、たとえば全身の逆運動学計算を実行する必要がある二足歩行ロボットに役立ちます。キネマティックチェーンを備えたほとんどのロボットには必要ありません。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_poses:各エンドエフェクタの目的の位置姿勢。getTipFrames関数で得られる名前と同じ順序で並べる
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
consistency_limits:ソリューション内の各関節が、与えられた初期状態の対応する関節から変化できる角度
solution:解ベクトル
solution_callback:逆運動学の解を検証するためのコールバック
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
context_state:(任意)このリクエストが行われているコンテキスト。関節の位置は、ik_seed_stateで与えられている位置と一致しない場合があります。逆運動学計算には、ik_seed_stateの値が使用され、このRobotStateは他の関節の値を提供するために使用します。このRobotStateは、二足歩行ロボットのバランスを考慮して計算するIKソルバーのように、コンテキストが必要な場合に使用されます。
-
virtual bool
getPositionFK
(const std::vector<std::string> &link_names, const std::vector<double> &joint_angles, std::vector<geometry_msgs::Pose> &poses) const = 0¶ 関節角度とリンクのリストを入力として、それらの位置姿勢を計算します。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
link_names:順運動学を計算する必要があるリンクのセット
joint_angles:順運動学が計算される関節状態
poses:結果の位置姿勢のリスト(getBaseFrameによって返される基準座標が使用される)
-
void
setValues
(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)¶ キネマティックチェーンIKソルバで使用するために、ソルバのパラメータを設定します。
- パラメータ
robot_description:このパラメーターは、計算対象のロボット運動学の識別子として使用できます。たとえば、ロボットの説明を含むROSパラメーターの名前。
group_name:このソルバーが構成されているグループ
base_frame:位置姿勢を解釈するための基準座標。これは、基底座標である場合とそうでない場合があります
tip_frame:チェーンの先端
search_discretization:ソルバーが冗長性をサンプリングするときの検索の離散化
-
void
setValues
(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::vector<std::string> &tip_frames, double search_discretization)¶ 非チェーンIKソルバーで使用するために、ソルバーのパラメーターを設定します。
- パラメータ
robot_description:このパラメーターは、計算対象のロボット運動学の識別子として使用できます。たとえば、ロボットの説明を含むROSパラメーターの名前。
group_name:このソルバーが構成されているグループ
base_frame:位置姿勢を解釈するための基準座標。これは、基底座標である場合とそうでない場合があります
tip_frames:キネマティックツリーのヒントのベクトル
search_discretization:ソルバーが冗長性をサンプリングするときの検索の離散化
-
bool
initialize
(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)¶ キネマティクスの初期化関数。キネマティックチェーンIKソルバーで使用します。
Instead of this method, use the method passing in a RobotModel! Default implementation returns false, indicating that this API is not supported.
- 戻り値
初期化が成功した場合はtrue、そうでない場合はfalse
- パラメータ
robot_description:このパラメーターは、計算対象のロボット運動学の識別子として使用できます。たとえば、ロボットの説明を含むROSパラメーターの名前。
group_name:このソルバーが構成されているグループ
base_frame:位置姿勢を解釈するための基準座標。これは、基底座標である場合とそうでない場合があります
tip_frame:チェーンの先端
search_discretization:ソルバーが冗長性をサンプリングするときの検索の離散化
-
bool
initialize
(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::vector<std::string> &tip_frames, double search_discretization)¶ キネマティクスの初期化関数。非チェーンIKソルバーで使用します。
Instead of this method, use the method passing in a RobotModel! Default implementation calls initialize() for tip_frames[0] and reports an error if tip_frames.size() != 1.
- 戻り値
初期化が成功した場合はtrue、そうでない場合はfalse
- パラメータ
robot_description:このパラメーターは、ロボットの運動学が計算される識別子として使用できます。たとえば、ロボットの説明を含むROSパラメーターの名前。
group_name:このソルバーが構成されているグループ
base_frame:位置姿勢を解釈するための基準座標。これは、基底座標である場合とそうでない場合があります
tip_frames:キネマティックツリーのヒントのベクトル
search_discretization:ソルバーが冗長性をサンプリングするときの検索の離散化
-
bool
initialize
(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector<std::string> &tip_frames, double search_discretization)¶ キネマティクスの初期化関数。キネマティックチェーンIKソルバーで使用します。
When returning false, the KinematicsPlugingLoader will use the old method, passing a robot_description. Default implementation returns false and issues a warning to implement this new API. TODO: Make this method purely virtual after some soaking time, replacing the fallback.
- 戻り値
初期化が成功した場合はtrue、そうでない場合はfalse
- パラメータ
robot_model
: - allow the URDF to be loaded much quicker by passing in a pre-parsed model of the robotgroup_name:このソルバーが構成されているグループ
base_frame:位置姿勢を解釈するための基準座標。これは、基底座標である場合とそうでない場合があります
tip_frames
: The tip of the chainsearch_discretization:ソルバーが冗長性をサンプリングするときの検索の離散化
-
virtual const std::string &
getGroupName
() const¶ ソルバーが動作しているグループの名前を返します。
- 戻り値
ソルバーが動作しているグループの文字列名
-
virtual const std::string &
getBaseFrame
() const¶ ソルバーが動作しているフレームの名前を返します。これは通常、リンク名です。ネームスペース(「/」プレフィックスなど)は使用しないでください。
- 戻り値
ソルバーが動作しているフレームの文字列名
-
virtual const std::string &
getTipFrame
() const¶ ソルバーが動作しているチェーンの先端フレームの名前を返します。これは通常、リンク名です。ネームスペース(「/」プレフィックスなど)は使用しないでください。
- 戻り値
ソルバーが動作しているチェーンの先端フレームの文字列名
-
virtual const std::vector<std::string> &
getTipFrames
() const¶ ソルバーが動作しているキネマティックツリーの先端フレームの名前を返します。これは通常、リンク名です。ネームスペース(「/」プレフィックスなど)は使用しないでください。
- 戻り値
ソルバーが動作しているキネマティックツリーの先端フレームの名前リスト
-
bool
setRedundantJoints
(const std::vector<unsigned int> &redundant_joint_indices)¶ 運動学ソルバーが使用する冗長関節のリストを設定します。 IKソルバーと冗長関節の選択によっては、設定が失敗する可能性があります。また、各冗長関節の離散化値をデフォルト値に設定します。
- 戻り値
入力された関節インデックスのいずれかが無効である(関節の数を超えている)場合はfalse
- パラメータ
redundant_joint_indices:冗長関節インデックスのリスト(getJointNamesで取得する関節のリストに対応)。
-
bool
setRedundantJoints
(const std::vector<std::string> &redundant_joint_names)¶ 運動学ソルバーが使用する冗長関節のリストを設定します。この関数は、setRedundantJointsの設定を呼び出すユーティリティ関数です
- 戻り値
入力された関節インデックスのいずれかが無効である(関節の数を超えている)場合はfalse
- パラメータ
redundant_joint_names
: The set of redundant joint names.
-
virtual void
getRedundantJoints
(std::vector<unsigned int> &redundant_joint_indices) const¶ 冗長関節のリストを取得します。
-
virtual const std::vector<std::string> &
getJointNames
() const = 0¶ すべての関節名を内部で使用される順序で返します。
-
virtual const std::vector<std::string> &
getLinkNames
() const = 0¶ すべてのリンク名を内部的で使用される順序で返します。
-
bool
supportsGroup
(const moveit::core::JointModelGroup *jmg, std::string *error_text_out = NULL) const¶ このソルバーが特定のJointModelGroupをサポートしているかどうかを確認します。
キネマティクスソルバーの実装が指定されたグループをサポートしているかどうかを確認するには、この関数をオーバーライドします。
この関数が追加される前に記述されたソルバーはすべてチェーングループのみをサポートするため、デフォルトの実装ではjmg->isChain()の結果が返されます。
- 戻り値
グループがサポートされている場合はtrue、サポートされていない場合はfalse。
- パラメータ
jmg:このIKソルバーが利用可能か問い合わせるプランニンググループ
error_text_out:このポインタがnullでなかった場合、グループがサポートされていない場合、サポートされていない理由の説明が格納されます。
-
void
setSearchDiscretization
(double sd)¶ すべての冗長関節の検索離散化値を設定します。
-
void
setSearchDiscretization
(const std::map<int, double> &discretization)¶ 冗長関節ごとに個別の離散化値を設定します。
このメソッドを呼び出すと、以前の離散化設定が置き換えられます。
- パラメータ
discretization:関節インデックスと離散化値のペア。
-
double
getSearchDiscretization
(int joint_index = 0) const¶ 検索の離散化の値を取得します。
-
std::vector<DiscretizationMethod>
getSupportedDiscretizationMethods
() const¶ サポートされている離散化検索タイプのリストを返します。この実装では、DiscretizationMethods::ONE検索のみをサポートします。
-
void
setDefaultTimeout
(double timeout)¶ タイムアウトが引数を使用して設定されていない関数の場合、この関数で設定された(およびKinematicsBase::DEFAULT_TIMEOUTに初期化された)デフォルトのタイムアウトが適用されます
-
double
getDefaultTimeout
() const¶ タイムアウトが引数を使用して指定されていない関数の場合、このデフォルトのタイムアウトが適用されます。
-
~KinematicsBase
()¶ インターフェイスの仮想デストラクタ。
-
typedef boost::function<void(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)>
KDL運動学計算プラグイン¶
Orocos-KDLライブラリ(https://www.orocos.org/kdl)を使った逆運動学計算アルゴリズムを利用できます。
KDLKinematicsPlugin¶
-
class
kdl_kinematics_plugin
::
KDLKinematicsPlugin
¶ KDLを使用した運動学アルゴリズムの実装。このバージョンでは、mimic関節も含め、あらゆる運動連鎖をサポートしています。
Inherits from kinematics::KinematicsBase
パブリック関数
-
KDLKinematicsPlugin
()¶ デフォルトコンストラクタ
-
bool
getPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, std::vector<double> &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに実現するための関節角度を計算します。
In contrast to the searchPositionIK methods, this one is expected to return the solution closest to the seed state. Randomly re-seeding is explicitly not allowed.
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
solution:解ベクトル
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, std::vector<double> &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
solution:解ベクトル
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, const std::vector<double> &consistency_limits, std::vector<double> &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
consistency_limits:ソリューション内の各関節が、与えられた初期状態の対応する関節から変化できる角度
solution:解ベクトル
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, std::vector<double> &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
solution:解ベクトル
solution_callback:逆運動学の解を検証するためのコールバック
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, const std::vector<double> &consistency_limits, std::vector<double> &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
consistency_limits:ソリューション内の各関節が、与えられた初期状態の対応する関節から変化できる角度
solution:解ベクトル
solution_callback:逆運動学の解を検証するためのコールバック
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
bool
getPositionFK
(const std::vector<std::string> &link_names, const std::vector<double> &joint_angles, std::vector<geometry_msgs::Pose> &poses) const¶ 関節角度とリンクのリストを入力として、それらの位置姿勢を計算します。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
link_names:順運動学を計算する必要があるリンクのセット
joint_angles:順運動学が計算される関節状態
poses:結果の位置姿勢のリスト(getBaseFrameによって返される基準座標が使用される)
-
bool
initialize
(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector<std::string> &tip_frames, double search_discretization)¶ キネマティクスの初期化関数。キネマティックチェーンIKソルバーで使用します。
When returning false, the KinematicsPlugingLoader will use the old method, passing a robot_description. Default implementation returns false and issues a warning to implement this new API. TODO: Make this method purely virtual after some soaking time, replacing the fallback.
- 戻り値
初期化が成功した場合はtrue、そうでない場合はfalse
- パラメータ
robot_model
: - allow the URDF to be loaded much quicker by passing in a pre-parsed model of the robotgroup_name:このソルバーが構成されているグループ
base_frame:位置姿勢を解釈するための基準座標。これは、基底座標である場合とそうでない場合があります
tip_frames
: The tip of the chainsearch_discretization:ソルバーが冗長性をサンプリングするときの検索の離散化
-
const std::vector<std::string> &
getJointNames
() const¶ すべての関節名を内部で使用される順序で返します。
-
const std::vector<std::string> &
getLinkNames
() const¶ すべてのリンク名を内部的で使用される順序で返します。
-
IKFast運動学計算プラグイン¶
IKFastは、OpenRAVEに含まれる逆運動学の解析解を自動で求めてくれるC++コードジェネレータです。
詳しい使い方は、以下の外部ドキュメントを参照してください。
http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/ikfast/ikfast_tutorial.html
IKFastKinematicsPlugin¶
-
class
_NAMESPACE_
::
IKFastKinematicsPlugin
¶ Inherits from kinematics::KinematicsBase
パブリック関数
-
bool
getPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, std::vector<double> &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに実現するための関節角度を計算します。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
solution:解ベクトル
error_code:失敗または成功の理由を示すエラーコード
-
bool
getPositionIK
(const std::vector<geometry_msgs::Pose> &ik_poses, const std::vector<double> &ik_seed_state, std::vector<std::vector<double>> &solutions, kinematics::KinematicsResult &result, const kinematics::KinematicsQueryOptions &options) const¶ エンドエフェクタの位置姿勢を入力として、それに到達できる関節角度を計算します。
このデフォルトの実装では、1つの解のみを返すため、結果は、ゼロで初期化された初期姿勢でgetPositionIK関数を呼び出すことと同等です。
- 戻り値
有効な解のセットが見つかった場合はtrue、そうでない場合はfalse。
- パラメータ
ik_poses:各エンドエフェクタの位置姿勢
ik_seed_state:逆運動学計算の初期値
solutions:有効な関節角を格納したベクトルのベクトル
result:クエリの結果を格納する構造体
options:使用される冗長性の離散化のタイプ。デフォルトの実装では、KinmaticSearches::NO_DISCRETIZATIONメソッドのみがサポートされます。他のものを要求すると失敗します。
-
bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, std::vector<double> &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドでは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
-
bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, const std::vector<double> &consistency_limits, std::vector<double> &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドでは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
the:冗長性を使って現在の位置から離れられる距離
-
bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, std::vector<double> &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドでは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
-
bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, const std::vector<double> &consistency_limits, std::vector<double> &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。この特定の方法は、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。consistent_limitは、初期状態で指定された位置の周りの特定の冗長範囲のみを検索するように指定します。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
consistency_limit:冗長性を使って現在の位置から離れることができる距離
-
bool
getPositionFK
(const std::vector<std::string> &link_names, const std::vector<double> &joint_angles, std::vector<geometry_msgs::Pose> &poses) const¶ 関節角度とリンクのリストを入力として、それらの位置姿勢を計算します。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
link_names:順運動学を計算する必要があるリンクのセット
joint_angles:順運動学が計算される関節状態
poses:結果の位置姿勢のリスト(getBaseFrameによって返される基準座標が使用される)
-
void
setSearchDiscretization
(const std::map<unsigned int, double> &discretization)¶ 冗長関節の離散化値を設定します。
このikfast実装では1つの冗長ジョイントが許可されるため、離散化マップ内の最初のエントリのみが使用されます。このメソッドを呼び出すと、以前の離散化設定が置き換えられます。
- パラメータ
discretization:関節インデックスと離散化値のペア。
-
bool
setRedundantJoints
(const std::vector<unsigned int> &redundant_joint_indices)¶ デフォルトのメソッドをオーバーライドして、冗長関節への変更を防ぎます。
-
bool
LMA運動学計算プラグイン¶
LMAKinematicsPlugin¶
-
class
lma_kinematics_plugin
::
LMAKinematicsPlugin
¶ KDLのLevenberg-Marquardt(LMA)ソルバーを使用した運動学アルゴリズムの実装。このバージョンは、mimic関節を除く、あらゆる運動連鎖をサポートします。
Inherits from kinematics::KinematicsBase
パブリック関数
-
LMAKinematicsPlugin
()¶ デフォルトコンストラクタ
-
bool
getPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, std::vector<double> &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに実現するための関節角度を計算します。
In contrast to the searchPositionIK methods, this one is expected to return the solution closest to the seed state. Randomly re-seeding is explicitly not allowed.
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
solution:解ベクトル
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, std::vector<double> &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
solution:解ベクトル
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, const std::vector<double> &consistency_limits, std::vector<double> &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
consistency_limits:ソリューション内の各関節が、与えられた初期状態の対応する関節から変化できる角度
solution:解ベクトル
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, std::vector<double> &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
solution:解ベクトル
solution_callback:逆運動学の解を検証するためのコールバック
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
bool
searchPositionIK
(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_seed_state, double timeout, const std::vector<double> &consistency_limits, std::vector<double> &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const¶ エンドエフェクタの位置姿勢を入力として、それに到達するために必要な関節角度を検索します。このメソッドは、冗長性(または他の数値計算)をサンプリングすることにより、解空間を「検索」することを目的としています。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
ik_pose:リンクの位置姿勢
ik_seed_state:逆運動学計算の初期値
timeout:ソルバーが使用できる時間(秒単位)
consistency_limits:ソリューション内の各関節が、与えられた初期状態の対応する関節から変化できる角度
solution:解ベクトル
solution_callback:逆運動学の解を検証するためのコールバック
error_code:失敗または成功の理由を示すエラーコード
options:その他のオプション。詳細については、KinematicsQueryOptionsの定義をご覧ください。
-
bool
getPositionFK
(const std::vector<std::string> &link_names, const std::vector<double> &joint_angles, std::vector<geometry_msgs::Pose> &poses) const¶ 関節角度とリンクのリストを入力として、それらの位置姿勢を計算します。
- 戻り値
有効な解が見つかった場合はtrue、そうでない場合はfalse
- パラメータ
link_names:順運動学を計算する必要があるリンクのセット
joint_angles:順運動学が計算される関節状態
poses:結果の位置姿勢のリスト(getBaseFrameによって返される基準座標が使用される)
-
bool
initialize
(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector<std::string> &tip_frames, double search_discretization)¶ キネマティクスの初期化関数。キネマティックチェーンIKソルバーで使用します。
When returning false, the KinematicsPlugingLoader will use the old method, passing a robot_description. Default implementation returns false and issues a warning to implement this new API. TODO: Make this method purely virtual after some soaking time, replacing the fallback.
- 戻り値
初期化が成功した場合はtrue、そうでない場合はfalse
- パラメータ
robot_model
: - allow the URDF to be loaded much quicker by passing in a pre-parsed model of the robotgroup_name:このソルバーが構成されているグループ
base_frame:位置姿勢を解釈するための基準座標。これは、基底座標である場合とそうでない場合があります
tip_frames
: The tip of the chainsearch_discretization:ソルバーが冗長性をサンプリングするときの検索の離散化
-
const std::vector<std::string> &
getJointNames
() const¶ すべての関節名を内部で使用される順序で返します。
-
const std::vector<std::string> &
getLinkNames
() const¶ すべてのリンク名を内部的で使用される順序で返します。
-