C++用ユーザライブラリ(MoveGroupInterface)の仕様

コンポーネント図

MoveGroupInterfaceは、ROS通信を使って、プランニング命令をROSのmove_groupサーバに送信します。

[MoveGroupInterface] -right-> [move_group] : ROS通信

move_groupサーバで提供されている各サービスとROS通信の詳細については、 move_groupサーバの仕様 を参照してください。

コードサンプル

本文書では、クラスの仕様のみを記述します。コードサンプルについては、以下の外部ドキュメント参照してください。

http://docs.ros.org/melodic/api/moveit_tutorials/html/doc/move_group_interface/move_group_interface_tutorial.html

MoveGroupInterface

class moveit::planning_interface::MoveGroupInterface

move_groupサーバによって提供されている各種ROSサービスを使用するためのクライアントクラス

このクラスでは、利便性を向上させるために多くの暗黙の設定が行われています。

関節角ベースの目標設定

目標には2つのタイプがあります。JointValueTargetは、各関節角(回転関節の場合は角度、prismatic関節の場合は位置)の値を目標として指定します。PoseTargetは、1つまたは複数のエンドエフェクタの位置姿勢を目標として指定します(プランナーは、位置姿勢に到達させるために必要な関節角度を自動で計算します)。両者のタイプのうちどちらか一方のみを計画に使用できます。setJointValueTarget関数を呼び出すと、関節角度ベースの目標が設定されます。setPoseTarget、setOrientationTarget、setRPYTarget、setPositionTarget関数のいずれかを呼び出すと、位置姿勢ベースの目標が設定されます。

bool setJointValueTarget(const std::vector<double> &group_variable_values)

関節角ベースの目標を設定し、動作計画に使用します。

group_variable_valuesには、getJointValueTarget().getJointModelGroup(getName())->getVariableNames()で得られる関節名の配列と同じ順序で、各関節角度値を設定する必要があります。

毎回全ての関節の角度値を設定する必要があります。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

値が範囲外の場合、falseが返されますが、値はまだ目標として設定されていることに注意してください。

bool setJointValueTarget(const std::map<std::string, double> &variable_values)

関節角ベースの目標を設定し、動作計画に使用します。

variable_valuesは、関節名と関節角度を対応付けた辞書形式です。グループ内の関節名が実際の目標を設定するために使用されます。グループに含まれない関節名は無視されます。モデルに関節名が見つからない場合、例外がスローされます。variable_valuesで指定されていない関節の目標は変更されません(ロボットのすべての関節角目標を現在の関節角にリセットするには、setJointValueTarget(getCurrentJointValues())を使用してください)。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

値が範囲外の場合、falseが返されますが、値はまだ目標として設定されていることに注意してください。

bool setJointValueTarget(const robot_state::RobotState &robot_state)

関節角ベースの目標を設定し、動作計画に使用します。

グループ内のすべての関節角の目標値をrobot_stateで指定された値に設定します。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

値が範囲外の場合、falseが返されますが、値はまだ目標として設定されていることに注意してください。

bool setJointValueTarget(const std::string &joint_name, const std::vector<double> &values)

関節角ベースの目標を設定し、動作計画に使用します。

joint_nameで指定される関節に対応した1つの値が必要です。値は、この関節の目標角度として設定されます。他の関節の目標角度は変更されません。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

値が範囲外の場合、falseが返されますが、値はまだ目標として設定されていることに注意してください。

bool setJointValueTarget(const std::string &joint_name, double value)

関節角ベースの目標を設定し、動作計画に使用します。

joint_nameで指定される関節は1自由度である必要があります。値は、この関節の目標角度として設定されます。他の関節の目標角度は変更されません。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

値が範囲外の場合、falseが返されますが、値はまだ目標として設定されていることに注意してください。

bool setJointValueTarget(const sensor_msgs::JointState &state)

関節角ベースの目標を設定し、動作計画に使用します。

stateは、関節の目標角度を設定するために使用されます。stateで指定されていない他の関節の目標角度は変更されません。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

値が範囲外の場合、falseが返されますが、値はまだ目標として設定されていることに注意してください。

bool setJointValueTarget(const geometry_msgs::Pose &eef_pose, const std::string &end_effector_link = "")

逆運動学を計算して、関節角度の目標を設定します。

setPoseTarget関数とは異なり、逆運動学を用いて単一の解を算出し関節角度の目標値として設定します(setPoseTarget関数の場合は、逆運動学の複数の解が考慮されます)。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

逆運動学で解が見つけられなかった場合、falseが返されますが、逆運動学計算の一部の結果はまだ目標として設定されていることに注意してください。

bool setJointValueTarget(const geometry_msgs::PoseStamped &eef_pose, const std::string &end_effector_link = "")

逆運動学を計算して、関節角度の目標を設定します。

setPoseTarget関数とは異なり、逆運動学を用いて単一の解を算出し関節角度の目標値として設定します(setPoseTarget関数の場合は、逆運動学の複数の解が考慮されます)。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

逆運動学で解が見つけられなかった場合、falseが返されますが、逆運動学計算の一部の結果はまだ目標として設定されていることに注意してください。

bool setJointValueTarget(const Eigen::Isometry3d &eef_pose, const std::string &end_effector_link = "")

逆運動学を計算して、関節角度の目標を設定します。

setPoseTarget関数とは異なり、逆運動学を用いて単一の解を算出し関節角度の目標値として設定します(setPoseTarget関数の場合は、逆運動学の複数の解が考慮されます)。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

逆運動学で解が見つけられなかった場合、falseが返されますが、逆運動学計算の一部の結果はまだ目標として設定されていることに注意してください。

bool setApproximateJointValueTarget(const geometry_msgs::Pose &eef_pose, const std::string &end_effector_link = "")

逆運動学を計算して、関節角度の目標を設定します。

setPoseTarget関数とは異なり、逆運動学を用いて単一の解を算出し関節角度の目標値として設定します(setPoseTarget関数の場合は、逆運動学の複数の解が考慮されます)。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

逆運動学で解が見つけられない場合、近似が使用されます。

bool setApproximateJointValueTarget(const geometry_msgs::PoseStamped &eef_pose, const std::string &end_effector_link = "")

逆運動学を計算して、関節角度の目標を設定します。

setPoseTarget関数とは異なり、逆運動学を用いて単一の解を算出し関節角度の目標値として設定します(setPoseTarget関数の場合は、逆運動学の複数の解が考慮されます)。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

逆運動学で解が見つけられない場合、近似が使用されます。

bool setApproximateJointValueTarget(const Eigen::Isometry3d &eef_pose, const std::string &end_effector_link = "")

逆運動学を計算して、関節角度の目標を設定します。

setPoseTarget関数とは異なり、逆運動学を用いて単一の解を算出し関節角度の目標値として設定します(setPoseTarget関数の場合は、逆運動学の複数の解が考慮されます)。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

逆運動学で解が見つけられない場合、近似が使用されます。

void setRandomTarget()

各関節角の目標をランダムに設定します。

この関数の呼び出しが行われると、以前に設定された位置、姿勢、位置姿勢目標の代わりに関節角ベースの目標が使用されます。

bool setNamedTarget(const std::string &name)

関節角の目標値をrememberJointValues関数によって以前に記憶された値に設定するか、SRDFファイルに記述された値に設定します。

const robot_state::RobotState &getJointValueTarget() const

現在設定されている関節の目標角を取得します。

位置姿勢ベースの目標設定

位置姿勢(または位置、姿勢)目標を設定すると、以前設定された関節角度ベースの目標が無効になります。

複数のエンドエフェクタを持つグループの場合、グループ内の各エンドエフェクタに位置姿勢目標を設定できます。位置姿勢目標を設定されていないエンドエフェクタは、任意の位置に移動されることがあります。

bool setPositionTarget(double x, double y, double z, const std::string &end_effector_link = "")

end_effector_linkで指定されるエンドエフェクタの目標位置を(x、y、z)形式で設定します。

end_effector_linkが指定されていない場合、getEndEffectorLink関数の戻り値(デフォルトのエンドエフェクタ)が使用されます。

既存の関節角度ベースの目標は、設定された新しい位置、方向、位置姿勢目標で置き換えられます。

bool setRPYTarget(double roll, double pitch, double yaw, const std::string &end_effector_link = "")

end_effector_linkで指定されるエンドエフェクタの姿勢目標を(ロール、ピッチ、ヨー)形式で設定します。

end_effector_linkが指定されていない場合、getEndEffectorLink関数の戻り値(デフォルトのエンドエフェクタ)が使用されます。

既存の関節角度ベースの目標は、設定された新しい位置、方向、位置姿勢目標で置き換えられます。

bool setOrientationTarget(double x, double y, double z, double w, const std::string &end_effector_link = "")

end_effector_linkで指定されるエンドエフェクタの姿勢目標をクォータニオン(x、y、z、w)形式で設定します。

end_effector_linkが指定されていない場合、getEndEffectorLink関数の戻り値(デフォルトのエンドエフェクタ)が使用されます。

既存の関節角度ベースの目標は、設定された新しい位置、方向、位置姿勢目標で置き換えられます。

bool setPoseTarget(const Eigen::Isometry3d &end_effector_pose, const std::string &end_effector_link = "")

end_effector_linkで指定されるエンドエフェクタの位置姿勢目標を設定します。

end_effector_linkが指定されていない場合、getEndEffectorLink関数の戻り値(デフォルトのエンドエフェクタ)が使用されます。

既存の関節角度ベースの目標は、設定された新しい位置、方向、位置姿勢目標で置き換えられます。

bool setPoseTarget(const geometry_msgs::Pose &target, const std::string &end_effector_link = "")

end_effector_linkで指定されるエンドエフェクタの位置姿勢目標を設定します。

end_effector_linkが指定されていない場合、getEndEffectorLink関数の戻り値(デフォルトのエンドエフェクタ)が使用されます。

既存の関節角度ベースの目標は、設定された新しい位置、方向、位置姿勢目標で置き換えられます。

bool setPoseTarget(const geometry_msgs::PoseStamped &target, const std::string &end_effector_link = "")

end_effector_linkで指定されるエンドエフェクタの位置姿勢目標を設定します。

end_effector_linkが指定されていない場合、getEndEffectorLink関数の戻り値(デフォルトのエンドエフェクタ)が使用されます。

既存の関節角度ベースの目標は、設定された新しい位置、方向、位置姿勢目標で置き換えられます。

bool setPoseTargets(const EigenSTL::vector_Isometry3d &end_effector_pose, const std::string &end_effector_link = "")

end_effector_linkの位置姿勢目標をリスト形式で設定します。

end_effector_linkが指定されていない場合、getEndEffectorLink関数の戻り値(デフォルトのエンドエフェクタ)が使用されます。

計画するとき、プランナーはリストから任意に選択されたある1つの位置姿勢へ移動する軌跡を見つけようとします。このグループに複数のエンドエフェクタが含まれる場合、グループ内のすべてのエンドエフェクタに対して、同じ数の位置姿勢目標が設定されなければなりません。計画が成功した場合、すべてのエンドエフェクタに対して、各目標リスト内の同じインデックスの位置姿勢に動かそうとします。すなわち、あるエンドエフェクタが目標リストの3番目の位置姿勢を採用した場合、グループ内の他のエンドエフェクタも、それぞれの目標リストの3番目の位置姿勢を選択します。重要ではないエンドエフェクタ(どの位置に移動しても良いエンドエフェクタ)は、そのend_effector_linkに対してclearPoseTarget関数を呼び出すことにより、位置姿勢目標設定を無効化できます。

既存の関節角度ベースの目標は、設定された新しい位置、方向、位置姿勢目標で置き換えられます。

bool setPoseTargets(const std::vector<geometry_msgs::Pose> &target, const std::string &end_effector_link = "")

end_effector_linkの位置姿勢目標をリスト形式で設定します。

end_effector_linkが指定されていない場合、getEndEffectorLink関数の戻り値(デフォルトのエンドエフェクタ)が使用されます。

計画するとき、プランナーはリストから任意に選択されたある1つの位置姿勢へ移動する軌跡を見つけようとします。このグループに複数のエンドエフェクタが含まれる場合、グループ内のすべてのエンドエフェクタに対して、同じ数の位置姿勢目標が設定されなければなりません。計画が成功した場合、すべてのエンドエフェクタに対して、各目標リスト内の同じインデックスの位置姿勢に動かそうとします。すなわち、あるエンドエフェクタが目標リストの3番目の位置姿勢を採用した場合、グループ内の他のエンドエフェクタも、それぞれの目標リストの3番目の位置姿勢を選択します。重要ではないエンドエフェクタ(どの位置に移動しても良いエンドエフェクタ)は、そのend_effector_linkに対してclearPoseTarget関数を呼び出すことにより、位置姿勢目標設定を無効化できます。

既存の関節角度ベースの目標は、設定された新しい位置、方向、位置姿勢目標で置き換えられます。

bool setPoseTargets(const std::vector<geometry_msgs::PoseStamped> &target, const std::string &end_effector_link = "")

end_effector_linkの位置姿勢目標をリスト形式で設定します。

end_effector_linkが指定されていない場合、getEndEffectorLink関数の戻り値(デフォルトのエンドエフェクタ)が使用されます。

計画するとき、プランナーはリストから任意に選択されたある1つの位置姿勢へ移動する軌跡を見つけようとします。このグループに複数のエンドエフェクタが含まれる場合、グループ内のすべてのエンドエフェクタに対して、同じ数の位置姿勢目標が設定されなければなりません。計画が成功した場合、すべてのエンドエフェクタに対して、各目標リスト内の同じインデックスの位置姿勢に動かそうとします。すなわち、あるエンドエフェクタが目標リストの3番目の位置姿勢を採用した場合、グループ内の他のエンドエフェクタも、それぞれの目標リストの3番目の位置姿勢を選択します。重要ではないエンドエフェクタ(どの位置に移動しても良いエンドエフェクタ)は、そのend_effector_linkに対してclearPoseTarget関数を呼び出すことにより、位置姿勢目標設定を無効化できます。

既存の関節角度ベースの目標は、設定された新しい位置、方向、位置姿勢目標で置き換えられます。

void setPoseReferenceFrame(const std::string &pose_reference_frame)

位置姿勢を設定する際に、基準座標名を省略した場合にデフォルトとして用いる基準座標を設定します。

bool setEndEffectorLink(const std::string &end_effector_link)

エンドエフェクタの親リンクを指定します。このend_effector_linkは、各目標設定関数でend_effector_linkが明示的に指定されていない場合に、デフォルトとして使用されます。

bool setEndEffector(const std::string &eef_name)

使用するエンドエフェクタの名前を設定します。EndEffectorLinkをこのエンドエフェクタの親リンクとして設定することと同じ効果があります。

void clearPoseTarget(const std::string &end_effector_link = "")

end_effector_linkに対して設定された位置姿勢目標を消去します。

void clearPoseTargets()

すべてのエンドエフェクタに設定された位置姿勢目標を消去します。

const geometry_msgs::PoseStamped &getPoseTarget(const std::string &end_effector_link = "") const

end_effector_linkに対して現在設定されている位置姿勢目標を取得します。 end_effector_linkが空の場合、getEndEffectorLink関数の戻り値(デフォルト値)が使用されます。end_effector_linkに複数の目標が設定されている場合、最初の目標が返されます。このend_effector_linkに位置姿勢目標が設定されていない場合、空の位置姿勢が返されます(orientation.xyzw == 0を確認してください)。

const std::vector<geometry_msgs::PoseStamped> &getPoseTargets(const std::string &end_effector_link = "") const

end_effector_linkで指定されるエンドエフェクタの現在設定されている位置姿勢目標を取得します。位置姿勢目標は、対応するsetPoseTarget関数呼び出しが行われた場合、複数のポーズで構成される場合もあります。それ以外の場合、1つの位置姿勢目標のみを含むベクトルが返されます。 end_effector_linkが空(デフォルト値)の場合、getEndEffectorLink関数の戻り値がデフォルトとして利用されます。

const std::string &getEndEffectorLink() const

現在のエンドエフェクタリンクを取得します。これは、setEndEffectorLink関数によって(または間接的にsetEndEffector関数によって)設定された値を返します。setEndEffectorLink関数が呼び出されなかった場合、グループに含まれるエンドエフェクタの親リンク名を報告します。複数のエンドエフェクタがある場合、そのうちの1つが返されます。そのようなリンクが不明な場合、空の文字列が返されます。

const std::string &getEndEffector() const

現在のエンドエフェクタ名を取得します。これは、setEndEffector関数によって(またはsetEndEffectorLink関数によって間接的に)設定された値を返します。setEndEffector関数が呼び出されなかった場合、この関数はこのグループに含まれるエンドエフェクタを報告します。複数のエンドエフェクタがある場合、そのうちの1つが返されます。エンドエフェクタが不明な場合、空の文字列が返されます。

const std::string &getPoseReferenceFrame() const

setPoseReferenceFrame関数によって設定された基準座標を取得します。デフォルトでは、ロボットモデルの基準座標が用いられます。

スタート位置から目標位置へのパスを計画し、その計画を実行します。

moveit::planning_interface::MoveItErrorCode asyncMove()

設定した目標に到達させる軌跡を計画および実行します。この呼び出しはブロックされません(軌跡の実行が完了するまで待機しません)。

actionlib::SimpleActionClient<moveit_msgs::MoveGroupAction> &getMoveGroupClient() const

MoveGroupInterfaceによって使用されるROSのmove_groupアクションクライアントを取得します。アクションクライアントを使用して、軌道の実行状態をモニタし、非同期実行中に軌道の実行を中止することができます。

moveit::planning_interface::MoveItErrorCode move()

設定した目標に到達させる軌跡を計画および実行します。この呼び出しは常にブロックします(軌跡の実行が完了するまで待機します)。実行時には非同期スピナーを開始する必要があります。

moveit::planning_interface::MoveItErrorCode plan(Plan &plan)

関節グループを現在の状態から設定した目標に移動する軌跡計画を行います。軌跡の実行はされません。計画の結果はplanに保存されます。

moveit::planning_interface::MoveItErrorCode asyncExecute(const Plan &plan)

計画を実行し、完了を待たずに終了します。成功時にtrueを返します。

moveit::planning_interface::MoveItErrorCode execute(const Plan &plan)

計画を実行し、完了を待って終了します。成功時にtrueを返します。

double computeCartesianPath(const std::vector<geometry_msgs::Pose> &waypoints, double eef_step, double jump_threshold, moveit_msgs::RobotTrajectory &trajectory, bool avoid_collisions = true, moveit_msgs::MoveItErrorCodes *error_code = NULL)

指定されたwaypointsを辿るCartesian pathを計算します。結果の軌跡は、エンドエフェクタ座標上で、最大でeef_stepのステップサイズ(メートル単位)になるよう計算されます。waypointsの基準座標には、setPoseReferenceFrame関数で設定された座標が使われます。ロボットのコンフィグレーション空間上での距離変化としてjump_thresholdで設定された値のみが許可されます(これは逆運動学の解が「ジャンプ」することを防ぐためです)。avoid_collisionsがtrueに設定された場合、障害物回避が行われます。障害物が回避できない場合、関数は失敗します。 この関数は、waypointsによって記述されたパスをどれだけ忠実に辿ることができたかを示す0.0〜1.0の値を返します。エラーの場合は-1.0を返します。

double computeCartesianPath(const std::vector<geometry_msgs::Pose> &waypoints, double eef_step, double jump_threshold, moveit_msgs::RobotTrajectory &trajectory, const moveit_msgs::Constraints &path_constraints, bool avoid_collisions = true, moveit_msgs::MoveItErrorCodes *error_code = NULL)

指定されたwaypointsを辿るCartesian pathを計算します。結果の軌跡は、エンドエフェクタ座標上で、最大でeef_stepのステップサイズ(メートル単位)になるよう計算されます。waypointsの基準座標には、setPoseReferenceFrame関数で設定された座標が使われます。ロボットのコンフィグレーション空間上での距離変化としてjump_thresholdで設定された値のみが許可されます(これは逆運動学の解が「ジャンプ」することを防ぐためです)。path_constraintsで指定された運動学的制約を軌道上の全ての点でチェックします。制約が満たされない場合、部分的な解が返されます。 0.0〜1.0の値を返します。これは、ウェイポイントによって記述されたパスの割合を示します。エラーの場合は-1.0を返します。avoid_collisionsがtrueに設定された場合、制約がチェックされるとともに障害物回避が行われます。障害物が回避できない場合、関数は失敗します。 この関数は、waypointsによって記述されたパスをどれだけ忠実に辿ることができたかを示す0.0〜1.0の値を返します。エラーの場合は-1.0を返します。

void stop()

軌道の実行が行われている場合は、それを停止します。

void allowLooking(bool flag)

ロボットが動作する前に視点を変えて周囲を見回すかどうかを指定します(デフォルトはtrue)

void allowReplanning(bool flag)

環境の変化を検出した場合に、ロボットが再計画するかどうかを指定します。

void constructMotionPlanRequest(moveit_msgs::MotionPlanRequest &request)

plan関数、またはmove関数からmove_groupサーバにリクエストを送信するためのMotionPlanRequestを作成します。

計画とアクションを複数利用する高レベルの関数

moveit::planning_interface::MoveItErrorCode pick(const std::string &object, bool plan_only = false)

オブジェクトをピックします。

この関数では、事前に用意された複数のデフォルト把持ポーズを使ってプランニングを試行します。

moveit::planning_interface::MoveItErrorCode pick(const std::string &object, const moveit_msgs::Grasp &grasp, bool plan_only = false)

把握ポーズを与えることでオブジェクトをピックします。

moveit::planning_interface::MoveItErrorCode pick(const std::string &object, const std::vector<moveit_msgs::Grasp> &grasps, bool plan_only = false)

把握ポーズの候補を与えることでオブジェクトをピックします。

引数のベクトルが空の場合、この関数はpick(const std::string &object)と同様に動作します。

moveit::planning_interface::MoveItErrorCode planGraspsAndPick(const std::string &object = "", bool plan_only = false)

オブジェクトをピックします。

moveit_msgs::GraspPlanningサービスの「plan_grasps」関数を呼び出して、最適な把握ポーズを計算します。

moveit::planning_interface::MoveItErrorCode planGraspsAndPick(const moveit_msgs::CollisionObject &object, bool plan_only = false)

オブジェクトをピックします。

moveit_msgs::GraspPlanningサービスの「plan_grasps」関数を呼び出して、最適な把握ポーズを計算します。

moveit::planning_interface::MoveItErrorCode place(const std::string &object, bool plan_only = false)

ワールドの安全な場所にオブジェクトをプレースします(安全な場所が自動で検出されます)。

moveit::planning_interface::MoveItErrorCode place(const std::string &object, const std::vector<moveit_msgs::PlaceLocation> &locations, bool plan_only = false)

指定された場所の候補のいずれかにオブジェクトをプレースします。

moveit::planning_interface::MoveItErrorCode place(const std::string &object, const std::vector<geometry_msgs::PoseStamped> &poses, bool plan_only = false)

指定された場所の候補のいずれかにオブジェクトをプレースします。

moveit::planning_interface::MoveItErrorCode place(const std::string &object, const geometry_msgs::PoseStamped &pose, bool plan_only = false)

指定された場所にオブジェクトをプレースします。

bool attachObject(const std::string &object, const std::string &link = "")

planning scene内のオブジェクトの名前を指定して、オブジェクトをロボットのリンクに接続します。リンク名が指定されていない場合、デフォルトのエンドエフェクタが使用されます。エンドエフェクタが無い場合、グループ内の最初のリンクが使用されます。オブジェクト名が指定されない場合、move_groupサーバ上でエラーが発生しますが、このインターフェイスによる要求は成功します。

bool attachObject(const std::string &object, const std::string &link, const std::vector<std::string> &touch_links)

planning scene内のオブジェクトの名前を指定して、オブジェクトをロボットのリンクに接続します。touch_links引数によってオブジェクトが接触できるリンクのセットを指定します。リンク名が指定されていない場合、デフォルトのエンドエフェクタが使用されます。エンドエフェクタが無い場合、グループ内の最初のリンクが使用されます。オブジェクト名が指定されない場合、move_groupサーバ上でエラーが発生しますが、このインターフェイスによる要求は成功することに注意してください。

bool detachObject(const std::string &name = "")

オブジェクトの接続を解除します。 name引数で接続されているオブジェクトの名前、またはオブジェクトが接続されているリンクの名前を指定します。nameが指定されておらず、接続されているオブジェクトが1つしかない場合は、そのオブジェクトが切り離されます。接続解除するオブジェクトが識別できない場合は、エラーが生成されます。

ロボットの状態をモニタする

bool startStateMonitor(double wait = 1.0)

ロボットの現在の状態についてのデータを受信するCurrentStateMonitorインスタンスを作成します。データを受信する作業をあらかじめ開始できるため、今後のgetCurrentStateなどの関数の呼び出しに時間がかからず、失敗する可能性が低くなります。

std::vector<double> getCurrentJointValues()

各関節の現在の角度を取得します(getJoints関数を参照)

robot_state::RobotStatePtr getCurrentState(double wait = 1)

waitで指定された時間の間、ロボットの現在の状態に関するデータを収集します。

geometry_msgs::PoseStamped getCurrentPose(const std::string &end_effector_link = "")

end_effector_linkで指定されたエンドエフェクタの位置姿勢を取得します。 end_effector_linkが指定されなかった場合、getEndEffectorLinkによって指定されるデフォルトのエンドエフェクタが想定されます。

std::vector<double> getCurrentRPY(const std::string &end_effector_link = "")

end_effector_linkで指定されたエンドエフェクタのロールピッチヨー(XYZ)を取得します。 end_effector_linkが指定されなかった場合、getEndEffectorLinkによって指定されるデフォルトのエンドエフェクタが想定されます。

std::vector<double> getRandomJointValues()

各関節のランダムな角度を取得します(getJoints関数を参照)

geometry_msgs::PoseStamped getRandomPose(const std::string &end_effector_link = "")

end_effector_linkで指定されるエンドエフェクタが到達可能な位置姿勢の中からランダムな位置姿勢を取得します。 end_effector_linkが指定されなかった場合、getEndEffectorLink関数によって指定されるエンドエフェクタが想定されます。

名前付き関節角構成を管理する

void rememberJointValues(const std::string &name)

現在の関節角度値を名前を付けて記録する。これらはsetNamedTarget関数で使用できます。これらの値は、クライアントでローカルに記録されます。他のクライアントはそれらにアクセスできません。

void rememberJointValues(const std::string &name, const std::vector<double> &values)

指定された関節角度値を名前を付けて記録する。これらはsetNamedTarget関数で使用できます。これらの値は、クライアントでローカルに記録されます。他のクライアントはそれらにアクセスできません。

const std::map<std::string, std::vector<double>> &getRememberedJointValues() const

現在記録されている名前と関節角度値のマップを取得します。

void forgetJointValues(const std::string &name)

名前を指定して記録された関節角度を消去する。

プランニングの制約を管理する

void setConstraintsDatabase(const std::string &host, unsigned int port)

制約情報を保存するデータベースサーバーの場所を設定します。

std::vector<std::string> getKnownConstraints() const

MongoDBデータベースから既知の制約の名前を読み取ります。

moveit_msgs::Constraints getPathConstraints() const

このMoveGroupInterfaceに現在設定されている制約を取得します。

戻り値

このインターフェイスに設定された現在のパス制約のコピー

bool setPathConstraints(const std::string &constraint)

使用するパス制約を設定します。制約は、MongoDBサーバから名前で検索されます。以前setPathConstraints関数の呼び出しで設定されたパス制約は置き換えられます。

void setPathConstraints(const moveit_msgs::Constraints &constraint)

使用するパス制約を設定します。この関数については、データベースサーバーは必要ありません。以前setPathConstraints関数の呼び出しで設定されたパス制約は置き換えられます。

void clearPathConstraints()

パス制約を使用しないことを指定します。以前setPathConstraints関数の呼び出しで設定されたパス制約はすべて削除されます。

パブリック関数

MoveGroupInterface(const Options &opt, const std::shared_ptr<tf2_ros::Buffer> &tf_buffer = std::shared_ptr<tf2_ros::Buffer>(), const ros::WallDuration &wait_for_servers = ros::WallDuration())

オプションoptを用いて、MoveGroupInterfaceインスタンスを作成します。

パラメータ
  • opt.: MoveGroupInterface::Options構造体。特定のコールバックキューでros::NodeHandleを渡す場合、ros::CallbackQueueタイプ(ROSで使用されるコールバックキューのデフォルトタイプ)である必要があります。

  • tf_buffer.: 使用するTF2_ROSバッファーインスタンスを指定します。指定されない場合、内部TF2_ROS TransformListenerとともに内部的に構築されます。

  • wait_for_servers.: アクションサーバーへの接続のタイムアウト。ゼロ時間は無制限の待機を意味します。

MoveGroupInterface(const std::string &group, const std::shared_ptr<tf2_ros::Buffer> &tf_buffer = std::shared_ptr<tf2_ros::Buffer>(), const ros::WallDuration &wait_for_servers = ros::WallDuration())

特定のグループのMoveGroupアクションのクライアントを構築します。

パラメータ
  • tf_buffer.: 使用するTF2_ROSバッファーインスタンスを指定します。指定されない場合、内部TF2_ROS TransformListenerとともに内部的に構築されます。

  • wait_for_servers.: アクションサーバーへの接続のタイムアウト。ゼロ時間は無制限の待機を意味します。

MoveGroupInterface(const MoveGroupInterface&)

このクラスは一意のリソース(アクションクライアント、スレッドなど)を所有しており、コピーする意味はあまりありません。参照渡し、移動、または必要に応じて複数のインスタンスを作成することを推奨します。

const std::string &getName() const

このインスタンスが動作するグループの名前を取得します。

const std::vector<std::string> getNamedTargets()

目標として使用可能な名前付きロボット状態の名前を取得します。SRDFファイルから各状態とデフォルト状態の両方を取得します。

robot_model::RobotModelConstPtr getRobotModel() const

RobotModelオブジェクトを取得します。

const ros::NodeHandle &getNodeHandle() const

このインスタンスのROSノードハンドルを取得します。

const std::string &getPlanningFrame() const

プランニングを行う際に用いられるフレームの名前を取得します。

const std::vector<std::string> &getJointModelGroupNames() const

利用可能なプランニンググループ名を取得します。

const std::vector<std::string> &getJointNames()

グループで使用可能なジョイントの名前をvector形式で取得します。

const std::vector<std::string> &getLinkNames()

ループで使用可能なリンクの名前をvector形式で取得します。

std::map<std::string, double> getNamedTargetValues(const std::string &name)

名前で指定されたロボット状態の関節角度を取得します。

const std::vector<std::string> &getActiveJoints() const

このインスタンスが動作するアクティブな(作動可能な)関節リストを取得します。

const std::vector<std::string> &getJoints() const

このインスタンスが動作するすべての関節リストを取得します(固定関節を含む)。

unsigned int getVariableCount() const

このグループの状態を記述するために使用される変数の数を取得します。これは、自由度の数以上の数になります。

bool getInterfaceDescription(moveit_msgs::PlannerInterfaceDescription &desc)

サーバによって読み込まれたプランニングプラグインの説明を取得します。

std::map<std::string, std::string> getPlannerParams(const std::string &planner_id, const std::string &group = "")

planner_idで指定されたプランナーのパラメータを取得します。

void setPlannerParams(const std::string &planner_id, const std::string &group, const std::map<std::string, std::string> &params, bool bReplace = false)

planner_idで指定されたプランナーのパラメータを設定します。

std::string getDefaultPlannerId(const std::string &group = "") const

デフォルトプランナー(グループを指定しない場合はグローバルデフォルトプランナー)を取得します。

void setPlannerId(const std::string &planner_id)

今後の計画に使用するプランナーを指定します。

const std::string &getPlannerId() const

現在のplanner_idを取得します。

void setPlanningTime(double seconds)

プランニング時に適用されるタイムアウト時間を指定します。

プランナーが中止する前に問題解決に利用できる時間を設定します。

void setNumPlanningAttempts(unsigned int num_planning_attempts)

最適解を得るために動作計画を繰り返す回数を設定します。デフォルト値は1です。

void setMaxVelocityScalingFactor(double max_velocity_scaling_factor)

最大関節速度を下げるためのスケーリング係数を設定します。許可される値は0~1です。ロボットモデルで指定された最大関節速度に係数が乗算されます。有効範囲外(係数が0.0に設定された場合を含む)の場合、係数はデフォルト値の1.0(最大関節速度)が用いられます。

void setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor)

最大関節加速度を減らすためのスケーリング係数を設定します。許可される値は0~1です。ロボットモデルで定義された最大関節加速度に係数が乗算されます。有効範囲外(係数が0.0に設定された場合を含む)の場合、係数はデフォルト値の1.0(最大関節加速度)が用いられます。

double getPlanningTime() const

setPlanningTime関数で設定された秒数を取得します

プランナーが中止する前に問題解決に利用できる時間を取得します。

double getGoalJointTolerance() const

関節角度ベースの目標に到達したと判断するために使用される許容値を取得します。これは、コンフィギュレーション空間上での各関節角の距離です。

double getGoalPositionTolerance() const

位置目標に到達したと判断するために使用される許容値を取得します。これは、エンドエフェクタが到達する必要がある球体の半径です。

double getGoalOrientationTolerance() const

姿勢目標に到達したと判断するために使用される許容値を取得します。これは、ロール、ピッチ、ヨーのラジアン単位の許容値です。

void setGoalTolerance(double tolerance)

目標を達成したと判断するために使用される許容値を設定します。関節角度ベースの目標の場合、これはコンフィギュレーション空間上での各関節角の距離になります(関節の種類に応じてラジアンまたはメートル)。位置姿勢目標の場合、これはエンドエフェクタが到達する必要がある球体の半径になります。この関数は、内部的にsetGoalPositionTolerance、setGoalOrientationTolerance、およびsetGoalJointTolerance関数を呼び出します。

void setGoalJointTolerance(double tolerance)

関節角度ベースの目標に移動するときにゴールに到達したと判断するために使用される角度許容値を設定します。

void setGoalPositionTolerance(double tolerance)

指定された位置姿勢に移動するときにゴールに到達したと判断するために使用される位置許容値を設定します。

void setGoalOrientationTolerance(double tolerance)

指定された位置姿勢に移動するときにゴールに到達したと判断するために使用される姿勢の許容値を設定します。

void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)

ワークスペースの境界を指定します。この境界は、プランニングで用いられる基準座標上で指定されます(つまり、ロボットのルートリンクの原点からの相対座標で指定されます)。これは、グループにロボットのルート関節が含まれる場合、例えば、ロボットのワールドに対する動きを計画する場合に役立ちます。

void setStartState(const moveit_msgs::RobotState &start_state)

現在のロボットの状態ではなく、異なる開始状態を考慮する必要がある場合、この関数はその状態を設定します。

void setStartState(const robot_state::RobotState &start_state)

現在のロボットの状態ではなく、異なる開始状態を考慮する必要がある場合、この関数はその状態を設定します。

void setStartStateToCurrentState()

プランニングの開始状態を、ROSのjoint_stateトピックから得られた現在のロボットの状態に設定します。

void setSupportSurfaceName(const std::string &name)

ピック/プレース操作の場合に使われる支持平面の名前を設定します。エンドエフェクタに接続されたオブジェクトは支持平面との接触も検出されます。

パブリック静的属性

const std::string ROBOT_DESCRIPTION = "robot_description"

ロボットのURDFの読み取り元のデフォルトROSパラメータ名。 「robot_description」に設定されています。

class MoveGroupInterfaceImpl

パブリック関数

MoveItErrorCode place(const std::string &object, const std::vector<geometry_msgs::PoseStamped> &poses, bool plan_only = false)

指定された場所の候補のいずれかにオブジェクトをプレースします。

struct Options

MoveGroupInterfaceクラスを構築するときに使用するオプションの設定。

公開メンバー

std::string group_name_

クラスインスタンスを初期化したグループ名。

std::string robot_description_

ロボットのURDFの読み取り元のROSパラメータ名(デフォルトと異なる場合)

robot_model::RobotModelConstPtr robot_model_

ROSパラメータ以外にも、使用するRobotModelのインスタンスも指定できます。

struct Plan

モーションプラン(ROSメッセージ形式)

公開メンバー

moveit_msgs::RobotState start_state_

プランニングに使用される開始状態。

moveit_msgs::RobotTrajectory trajectory_

ロボットの軌跡(start_state_と同じ関節が含まれていない場合があります)

double planning_time_

プランニングにかかった時間。

PlanningSceneInterface

class moveit::planning_interface::PlanningSceneInterface

ワールドを管理する

std::vector<std::string> getKnownObjectNames(bool with_type = false)

ワールドのすべての既知のオブジェクトの名前を取得します。with_typeがtrueに設定されている場合、既知のタイプを持つオブジェクトのみを返します。

std::vector<std::string> getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz, bool with_type, std::vector<std::string> &types)

指定領域(getPlanningFrame関数によって設定された基準座標を使用)内にある既知のオブジェクトの名前を取得します。

with_typeがtrueに設定されている場合、既知のタイプを持つオブジェクトのみを返します。

std::vector<std::string> getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz, bool with_type = false)

指定領域(getPlanningFrame関数によって設定された基準座標を使用)内にある既知のオブジェクトの名前を取得します。with_typeがtrueに設定されている場合、既知のタイプを持つオブジェクトのみを返します。

std::map<std::string, geometry_msgs::Pose> getObjectPoses(const std::vector<std::string> &object_ids)

オブジェクトIDリストで指定されたオブジェクトから位置姿勢を取得します。

std::map<std::string, moveit_msgs::CollisionObject> getObjects(const std::vector<std::string> &object_ids = std::vector<std::string>())

オブジェクトIDリストで指定されたオブジェクトを取得します。 IDが指定されない場合、すべての既知のオブジェクトを返します。

std::map<std::string, moveit_msgs::AttachedCollisionObject> getAttachedObjects(const std::vector<std::string> &object_ids = std::vector<std::string>())

オブジェクトIDリストで指定されるロボットに接続されたオブジェクトを取得します。 IDが指定されない場合、接続されているすべてのオブジェクトを返します。

bool applyCollisionObject(const moveit_msgs::CollisionObject &collision_object)

オブジェクトをplanning sceneに同期的に追加します。planning sceneの更新情報は、move_groupの発行するROSトピックを購読しない限り、他のPlanningSceneMonitorには送信されません。

bool applyCollisionObject(const moveit_msgs::CollisionObject &collision_object, const std_msgs::ColorRGBA &object_color)

オブジェクトをplanning sceneに同期的に追加します。planning sceneの更新情報は、move_groupの発行するROSトピックを購読しない限り、他のPlanningSceneMonitorには送信されません。

bool applyCollisionObjects(const std::vector<moveit_msgs::CollisionObject> &collision_objects, const std::vector<moveit_msgs::ObjectColor> &object_colors = std::vector<moveit_msgs::ObjectColor>())

オブジェクトをplanning sceneに同期的に追加します。planning sceneの更新情報は、move_groupの発行するROSトピックを購読しない限り、他のPlanningSceneMonitorには送信されません。object_colorsでIDが指定されていない場合、collision_objectsの対応するオブジェクトIDが使用されます。

bool applyAttachedCollisionObject(const moveit_msgs::AttachedCollisionObject &attached_collision_object)

ロボットに接続されたオブジェクトをplanning sceneに同期的に追加します。planning sceneの更新情報は、move_groupの発行するROSトピックを購読しない限り、他のPlanningSceneMonitorには送信されません。

bool applyAttachedCollisionObjects(const std::vector<moveit_msgs::AttachedCollisionObject> &attached_collision_objects)

ロボットに接続されたオブジェクトをplanning sceneに同期的に追加します。planning sceneの更新情報は、move_groupの発行するROSトピックを購読しない限り、他のPlanningSceneMonitorには送信されません。

bool applyPlanningScene(const moveit_msgs::PlanningScene &ps)

move_groupサーバのplanning sceneを指定されたplanning scene情報で同期的に更新します。planning sceneの更新情報は、move_groupの発行するROSトピックを購読しない限り、他のPlanningSceneMonitorには送信されません。

void addCollisionObjects(const std::vector<moveit_msgs::CollisionObject> &collision_objects, const std::vector<moveit_msgs::ObjectColor> &object_colors = std::vector<moveit_msgs::ObjectColor>()) const

ROSの/planning_sceneトピックを使用して、オブジェクトをワールドに追加します。 メッセージのobject.operationがobject.ADDに設定されていることを確認してください。

ワールドの更新は非同期に実行されます。この関数を呼び出した直後にオブジェクトを使用可能にする必要がある場合は、代わりにapplyCollisionObjectsの使用を検討してください。

void removeCollisionObjects(const std::vector<std::string> &object_ids) const

ROSの/planning_sceneトピックを使用して、ワールドからオブジェクトを削除します。

ワールドの更新は非同期に実行されます。この関数を呼び出した直後にオブジェクトを削除する必要がある場合は、代わりにapplyCollisionObjectsの使用を検討してください。