UFactory社が販売する,xArmというマニピュレータがありますが,手先に独自のパーツを取り付け,urdfをカスタマイズしたい場合があります.今回は,urdfを変更し,moveit setup assistantにて自動生成されたパッケージから,実機に対応させる手順をやりましたので,備忘録として残しておきます.
なお,ROSはNoetic, xArm6を使っています.
目次
目的
独自のUrdfを使って,実機のxArmを動かすことです.これはすでに用意されているものとします.
事前準備
moveit setup assistant
setup assistantを用いて,collisionなどを設定します.これはmoveitのtutorialが参考になると思います.
https://ros-planning.github.io/moveit_tutorials/doc/setup_assistant/setup_assistant_tutorial.html
setup assistantは以下のコマンドで実行できます.
roslaunch moveit_setup_assistant setup_assistant.launch
実機用のlaunch file作成
予め,xArm rosのソースコードがダウンロードされているとします.
以下の手順では,本家の実機用launch file(realMove_exec.launch)を使って行っていきます.
まず,demo.launchをコピーして,適当な名前に変更します.
本体立ち上げ処理
xarm6_server.launchを引っ張ってきます.
<include file="$(find xarm_bringup)/launch/xarm6_server.launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
<arg name="report_type" value="$(arg report_type)" />
<arg name="use_moveit" value="true" />
<arg name="ns" value="$(arg xarm_hw_ns)" />
<arg name="velocity_control" value="$(arg velocity_control)" />
<arg name="enforce_limits" value="$(arg enforce_limits)" />
<arg name="baud_checkset" value="$(arg baud_checkset)" />
<arg name="default_gripper_baud" value="$(arg default_gripper_baud)" />
</include>
robot_ipなどのargは自動で生成されたmoveitのLaunch fileにはないので,launch file先頭に追加します.
<arg name="robot_ip" />
<arg name="report_type" default="normal" />
<!-- load the default move_group planner (not xarm_simple_planner) -->
<arg name="show_rviz" default="true" />
<!-- NO_GUI_CTRL means that Rviz configuration is just for display purpose, no (Moveit) control panel loaded -->
<arg name="no_gui_plan" default="false" />
<arg name="xarm_hw_ns" default="xarm" />
<arg name="ext_ns" default="" />
<arg name="velocity_control" default="false"/>
<arg name="enforce_limits" default="true" />
<arg name="baud_checkset" default="true" />
<arg name="default_gripper_baud" default="2000000" />
<arg name="jnt_stat_pub_rate" default="10" />
<arg name="jnt_stat_source" value="[$(arg xarm_hw_ns)/joint_states]" />
ところで,xarm6_server.launchはxarm6_params.yamlというファイルをmoveit configのパッケージから参照します.なので,xarm rosからダウンロードしたmoveit configにあるxarm6_params.yamlをコピーし,当該パッケージのconfigフォルダに配置します.
ros controller立ち上げ処理
xarm_traj_controllerを起動させます.
<rosparam file="$(find xarm_controller)/config/xarm6_traj_controller.yaml" command="load" ns="$(arg xarm_hw_ns)"/>
<arg name="xarm_traj_controller" value="$(eval 'xarm6_traj_controller_velocity' if arg('velocity_control') else 'xarm6_traj_controller')" />
<node
name="traj_controller_spawner"
pkg="controller_manager"
type="spawner"
respawn="false"
output="screen"
ns="$(arg xarm_hw_ns)"
args="$(arg xarm_traj_controller)"/>
<!-- <remap from="/follow_joint_trajectory" to="xarm/xarm6_traj_controller/follow_joint_trajectory"/> -->
<remap from="/follow_joint_trajectory" to="$(arg xarm_hw_ns)/$(arg xarm_traj_controller)/follow_joint_trajectory"/>
find xarm_controllerとしているので,work space内にxarm_controller packageを追加しておいてください.
joint state publisher, robot state publisher起動
下記の記述を追加します.
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="/use_gui" value="$(arg use_gui)"/>
<param name="/rate" value="$(arg jnt_stat_pub_rate)"/>
<rosparam param="/source_list" subst_value="True">$(arg jnt_stat_source)</rosparam>
</node>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" />
demo.launchではmoveit_controller_manager変数をfakeとしているのでデフォルトでjoint state publisher, robot state publisherが実行されますが,今回はそれを変更するので,条件分岐により,実行されません.なので,上記の記述が必要になります.
controllers.yamlの読み込み処理
まず,ダウンロードしたmoveit configのcontrollers.yamlを当該moveit config packageにコピーしておきます.
次に,moveit_controller_manager変数の値を適当にfake以外の値に変更します.私はrealという値に変更しました.
<arg name="moveit_controller_manager" default="real" />
moveit_controller_manager変数を修正する理由は,controllers.yamlがtrajectory_execution.launch.xmlにおいて,下記のようにコマンドで読み込まれるためです.
<include file="$(dirname)/$(arg moveit_controller_manager)_moveit_controller_manager.launch.xml" pass_all_args="true" />
なので,新たにreal_moveit_controller_manager.launch.xmlをlaunchフォルダ内に作成し,下記のように記述します.これはxarm rosのxarm6_moveit_controller_manager.launch.xmlからコピーしてきたものです.
<launch>
<!-- execute the trajectory in 'interpolate' mode or jump to goal position in 'last point' mode -->
<param name="moveit_controller_manager" value="moveit_simple_controller_manager/MoveItSimpleControllerManager"/>
<!-- Disable the exec duration monitoring -->
<param name="trajectory_execution/execution_duration_monitoring" value="false"/>
<!-- The rest of the params are specific to this plugin -->
<rosparam file="$(find xarm6_moveit_config)/config/controllers.yaml"/>
</launch>
以上にて終了です.