Python用ユーザライブラリ(moveit_commander)の仕様

クラス図

moveit_commanderは、boost::pythonを使って、C++のMoveGroupInterfaceを呼び出します。 その際に、MoveGroupInterfaceWrapperクラスを用います。

MoveGroupInterface <|-- MoveGroupInterfaceWrapper
MoveGroupInterfaceWrapper .. moveit_commander

C++で実装されたMoveGroupInterfaceの詳細については、 C++用ユーザライブラリ(MoveGroupInterface)の仕様 を参照してください。

コンポーネント図

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

[moveit_commander(MoveGroupInterface)] -right-> [move_group] : ROS通信

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

コードサンプル

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

http://docs.ros.org/melodic/api/moveit_tutorials/html/doc/move_group_python_interface/move_group_python_interface_tutorial.html

RobotCommander

class moveit_commander.RobotCommander(robot_description='robot_description', ns='')
get_current_state()

ロボットの現在の状態をROSのRobotStateメッセージ形式で取得します。

get_current_variable_values()

関節名と関節角度をマッピングさせた辞書形式で取得します。関節値は複数の変数からなる場合もあることに留意してください。

get_default_owner_group(joint_name)

引数として指定された関節名を含んだ最小のグループ名(最小の関節数のグループ名)を取得します。

get_group(name)
パラメータ

str (name) -- 名前

戻り値の型

moveit_commander.MoveGroupCommander

get_group_names()

ロボットモデルに対して定義されたグループ名のリストを取得します。

get_joint(name)
パラメータ

str (name) -- 名前

戻り値の型

moveit_commander.robot.Joint

例外

exception -- MoveItCommanderException

get_joint_names(group=None)

グループを構成するすべての可動関節(mimic関節と固定関節を除く)の名前を取得します。グループ名が指定されない場合、ロボットモデル内のすべての関節(固定関節とmimic関節を含む)の名前を取得します。

パラメータ

str (name) -- 名前

戻り値の型

moveit_commander.robot.Link

例外

exception -- MoveItCommanderException

グループを構成するリンクを取得します。グループ名が指定されない場合、ロボットモデル内のすべてのリンクが返されます。

get_planning_frame()

プランニングの実行対象となっている基準座標名を取得します

get_robot_markers(*args)

このロボットを構成するマーカーのMarkerArrayを取得します。

使用法:

(引数なし):現在のロボットの状態に対するすべてのマーカーを取得する。 state (RobotState形式):stateで指定された状態に対するマーカーを取得する。 values (辞書形式):valuesで指定された状態に対するマーカーを取得する。 values, links (辞書形式、リスト形式):valuesで指定された状態に対するlinksで指定されたリンクに対応するマーカーを取得する。 group (文字列):groupのすべてのマーカーを取得する。 group, values (文字列、辞書形式):指定されたgroupに対して、valuesで指定された状態に対応するマーカーを取得する。

ロボットモデルのルートリンクの名前を取得します。

has_group(name)
パラメータ

str (name) -- 名前

戻り値の型

bool

MoveGroupCommander

class moveit_commander.MoveGroupCommander(name, robot_description='robot_description', ns='')

指定されたグループに対してコマンドを実行します。

__init__(name, robot_description='robot_description', ns='')

このインターフェースを利用する対象となるグループ名を指定します。初期化に失敗した場合、例外をスローします。

allow_looking(value)

動作計画の中で視点を変更することを有効/無効化します。

allow_replanning(value)

再プランを有効/無効化します。

attach_object(object_name, link_name='', touch_links=[])

planning scene内に存在するオブジェクトの名前を指定しリンクに対して接続します。接続対象のリンクは、第2引数で指定します。対象のリンクを指定しない場合、エンドエフェクタのリンクが使用されます。エンドエフェクタのリンクが存在しない場合、グループ内の最初のリンクが使用されます。どのリンクも選択できない場合、リクエストが失敗します。要求が正常にmove_groupサーバに送信された場合、Trueが返されます。ただし、Trueが返った場合でも、move_groupによって固定が実際に適用されたかどうかは確認されません。

clear_path_constraints()

現在設定されている動作計画に対する全てのパス制約をクリアします。

clear_pose_target(end_effector_link)

end_effector_linkに対する目標姿勢をクリアします。

clear_pose_targets()

すべての目標姿勢をクリアします。

clear_trajectory_constraints()

動作計画中に適用される全ての軌道制約をクリアします。

compute_cartesian_path(waypoints, eef_step, jump_threshold, avoid_collisions=True, path_constraints=None)

指定されたポーズ列(waypoints)を線形補完した動きをエンドエフェクタにさせるための動作計画を行います。eef_stepで指定された間隔(メートル単位)毎に動作が計算されます。jump_thresholdは、計画結果の軌跡を構成する連続する各点の間のコンフィギュレーション空間上での最大距離を指定します。path_constraintsによって指定された制約を軌道の全ての点で満たすように動作計画が行われます。制約を全点で満たすことができなかった場合、部分的な動作計画が返されます。関数の戻り値は、指定されたポーズ列をどれだけ忠実に追跡することができたかの評価値と、計画された軌跡(RobotTrajectory形式)のタプル形式です。

detach_object(name='')

リンクの名前を指定すると、そのリンクからオブジェクト(複数可)を取り外します。指定されたリンク名が存在しない場合、指定された名前は、オブジェクト名として解釈されます。名前が指定されない場合、グループ内の全てのリンクに接続されている全てのオブジェクトが取り外されます。

execute(plan_msg, wait=True)

計画したパスを実行します。

forget_joint_values(name)

保存された関節角を消去します。

get_active_joints()

このグループの有効な関節リストを取得します。

get_current_joint_values()

現在の関節角度をリストとして取得します(ROSの/joint_statesトピックで公開されているのと同じ値です)。

get_current_pose(end_effector_link='')

エンドエフェクタの現在の姿勢を取得します。エンドエフェクタが無い場合、例外をスローします。

get_current_rpy(end_effector_link='')

エンドエフェクタの姿勢を[ロール、ピッチ、ヨー]形式のリストで取得します。エンドエフェクタが無い場合、例外をスローします。

エンドエフェクタとして定義されたリンクの名前を取得します。エンドエフェクタが無い場合、空の文字列を返します。

get_goal_joint_tolerance()

関節角目標を達成したと判断する際の許容値を取得します。

get_goal_orientation_tolerance()

姿勢目標または位置姿勢目標に移動する際の達成と判断する許容値を取得します。許容値は、エンドエフェクタの目標点までの姿勢誤差(ロール、ピッチ、ヨー)として設定されます。

get_goal_position_tolerance()

位置目標または姿勢目標に移動する際の達成と判断する許容値を取得します。許容値は、エンドエフェクタのターゲット原点を中心とする球の半径として設定されます。

get_goal_tolerance()

目標からの誤差を(関節角誤差、位置誤差、方向誤差)のタプル形式で取得します。

get_interface_description()

プランナーインターフェースの説明(プランナーIDのリスト)を取得します。

get_jacobian_matrix(joint_values)

各関節のヤコビ行列をリスト形式で取得します。

get_joints()

関節名をリスト形式で取得します。

get_known_constraints()

データベース(warehouse)から、このグループに紐づけられた制約の名前リストを取得します。

get_name()

初期化の際に設定したグループ名を取得します。

get_named_target_values(target)

名前付き関節角目標の関節値を辞書形式で取得します。

get_named_targets()

名前付き関節角目標の全ての名前リストを取得します。

get_path_constraints()

現在設定されているパス制約をmoveit_msgs.Constraints形式で取得します。

get_planner_id()

現在設定されているプランナーのplanner_idを取得します。

get_planning_frame()

計画が実行される基準座標の名前を取得します。

get_planning_time()

動作計画のタイムアウト時間を指定します。

get_pose_reference_frame()

エンドエフェクタの姿勢表現に使われる基準座標を取得します。

get_remembered_joint_values()

remember_joint_valuesで記録された関節角目標を名前が対応付けられた辞書形式で取得します。

get_trajectory_constraints()

現在設定されている軌道制約をmoveit_msgs.Constraints形式で取得します。

get_variable_count()

このグループの状態をパラメータ化する際に使用される変数の数を返します(関節の自由度数以上の値になります)。

go(joints=None, wait=True)

目標を設定し、グループを指定された目標に移動します。

このグループにエンドエフェクタして設定されたリンクがあるかどうかを確認します。

pick(object_name, grasp=[], plan_only=False)

名前で指定されたオブジェクトをピックします。Graspメッセージ、またはGraspメッセージのリストを引数として指定します。

place(object_name, location=None, plan_only=False)

指定されたオブジェクトを環境内の指定された場所に置くか、場所が指定されていない場合はワールドのどこかに安全な場所に置きます。

plan(joints=None)

設定済みの目標を達成するための動作計画を行います。戻り値は、RobotTrajectory形式です。引数で関節角が指定された場合は、関節角を目標とした動作計画を行います。

remember_joint_values(name, values=None)

名前で指定された関節角の状態を記録します。値が指定されない場合、グループの全体の関節角の状態が記録されます。

set_constraints_database(host, port)

制約をロードするために接続するデータベースのホスト名とポート番号を設定します。

エンドエフェクタと見なすリンクの名前を設定します。

set_goal_joint_tolerance(value)

目標関節角を達成と判断する際の許容値を設定します。

set_goal_orientation_tolerance(value)

エンドエフェクタの目標姿勢を達成と判断する際の許容値を設定します。

set_goal_position_tolerance(value)

エンドエフェクタの目標位置を達成と判断する際の許容値を設定します。

set_goal_tolerance(value)

関節角、位置、および姿勢を達成と判断する際の許容値を同時に設定します。

set_joint_value_target(arg1, arg2=None, arg3=None)

関節角目標を指定します。 第一引数の型がdict、list、JointStateメッセージのいずれかである場合、他の引数は設定できません。 dict型の場合、関節名とその目標角度のペアを指定する必要があります。list型の場合、グループのすべての関節の角度値を指定する必要があります。 JointStateメッセージの場合は、関節角度を選択的に指定できます。 第一引数の型が文字列の場合、第二引数には、関節角度または関節角度のリストのいずれかを設定します。これは、特定の関節を特定の角度に設定する命令として解釈されます。第一引数の型がPoseまたはPoseStampedの場合、第二引数と第三引数の両方を定義できます。第二引数または第三引数が定義されている場合、それらの型は文字列またはbool型でなければなりません。文字列型の引数は、Pose目標が指定されたエンドエフェクタの名前です(指定されない場合、デフォルトのエンドエフェクタが使用されます)。第三引数のboolは、指定されたPoseが近似であるかどうかを決定するために使用されます(デフォルトはfalse)。Pose目標を用いると、逆運動学を用いるて関節目標を設定できます。ここでは、プランナーを用いて逆運動学の計算を複数試行するわけではありません。Poseから計算されたある1つの逆運動学の解がプランナーに送信されます。

set_max_acceleration_scaling_factor(value)

最大関節加速度を減らすためのスケーリング係数を設定します。許可される値は0~1です。

set_max_velocity_scaling_factor(value)

最大関節速度を下げるためのスケーリング係数を設定します。許可される値は0~1です。

set_named_target(name)

関節角目標を名前で設定します。あらかじめremember_joint_valuesで記憶された名前、またはSRDFファイルに記述された名前を指定できます。

set_num_planning_attempts(num_planning_attempts)

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

set_orientation_target(q, end_effector_link='')

エンドエフェクタの目標姿勢を指定します。姿勢のみが指定され、位置については任意の位置が許容されます。

set_path_constraints(value)

使用するパス制約を指定します(制約はデータベースから読み取られます)。

set_planner_id(planner_id)

動作計画時に使用するプランナーを指定します。

set_planning_time(seconds)

動作計画のタイムアウト時間を指定します。

set_pose_reference_frame(reference_frame)

エンドエフェクタの位置姿勢を設定する際に用いられる基準座標を設定します。

set_pose_target(pose, end_effector_link='')

エンドエフェクタの位置姿勢を設定します。Poseメッセージ、PoseStampedメッセージ、または6次元のリスト形式で指定してください。

set_pose_targets(poses, end_effector_link='')

エンドエフェクタの位置姿勢を設定します。予想される入力は位置姿勢のリストです。Poseメッセージ、[x、y、z、rot_x、rot_y、rot_z]の6次元のリスト形式、または[x、y、z、qx、qy、qz、qw]の7次元のリスト形式で指定してください。

set_position_target(xyz, end_effector_link='')

エンドエフェクタの目標位置を指定します。位置のみが指定され、姿勢については任意として解釈されます。

set_random_target()

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

set_rpy_target(rpy, end_effector_link='')

エンドエフェクタの目標姿勢を指定します。姿勢のみが指定され、位置については任意の位置が許容されます。

set_start_state(msg)

開始状態を指定します。

msg : moveit_msgs/RobotState

>>> from moveit_msgs.msg import RobotState
>>> from sensor_msgs.msg import JointState
>>> joint_state = JointState()
>>> joint_state.header = Header()
>>> joint_state.header.stamp = rospy.Time.now()
>>> joint_state.name = ['joint_a', 'joint_b']
>>> joint_state.position = [0.17, 0.34]
>>> moveit_robot_state = RobotState()
>>> moveit_robot_state.joint_state = joint_state
>>> group.set_start_state(moveit_robot_state)
set_support_surface_name(value)

ピックアンドプレース命令を実行する際の支持平面名を設定します。

set_trajectory_constraints(value)

軌道制約を設定します。

set_workspace(ws)

ロボットのワークスペースを[]、[minX、minY、maxX、maxY]、または[minX、minY、minZ、maxX、maxY、maxZ]形式で設定します。

shift_pose_target(axis, value, end_effector_link='')

エンドエフェクタの現在の位置姿勢を取得し、[X、Y、Z、R、P、Y]の6次元の形式で指定された差分値を適用し、新しい目標姿勢として設定します。

stop()

現在の実行を停止します。

PlanningSceneInterface

class moveit_commander.PlanningSceneInterface(ns='', synchronous=False, service_timeout=5.0)

planning sceneを更新するためのインターフェース

__init__(ns='', synchronous=False, service_timeout=5.0)

planning sceneを更新するためのインターフェースを作成します。C++クラスの呼び出しとROSトピックの発行の両者を使います。

add_box(name, pose, size=(1, 1, 1))

planning sceneに箱型を追加します。

add_cylinder(name, pose, height, radius)

planning sceneに円柱を追加します。

add_mesh(name, pose, filename, size=(1, 1, 1))

planning sceneにメッシュ形状を追加します。

add_plane(name, pose, normal=(0, 0, 1), offset=0)

planning sceneに平面を追加します。

add_sphere(name, pose, radius=1)

planning sceneに球体を追加します。

get_attached_objects(object_ids=[])

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

get_known_object_names(with_type=False)

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

get_known_object_names_in_roi(minx, miny, minz, maxx, maxy, maxz, with_type=False)

指定範囲内にあるオブジェクトの名前を取得します。 範囲指定は、get_planning_frameによって設定される基準座標上で解釈されます。with_typeがtrueに設定されている場合、既知のタイプを持つオブジェクトのみを返します。

get_object_poses(object_ids)

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

get_objects(object_ids=[])

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

remove_attached_object(link, name=None)

planning sceneからロボットに接続されたオブジェクトを削除します。名前が指定されていない場合、リンクに接続されているすべてのオブジェクトを削除します。

remove_world_object(name=None)

planning sceneからオブジェクトを削除します。名前が指定されていない場合はすべてのオブジェクトを削除します。