【OpenRR】RustでRobot!#04 「Ufactory Lite6」
4-1. はじめに
こんにちは、Smile Roboticsの内山です。UfactoryのLite6というロボットを動かしてみます。
4-1-1. Lite6とは
Lite6は、中国の深センにあるUfactory社のロボットアームです。
GitHubの公式のリポジトリ
4-1-2. ロボットのセットアップ
Quick start guideにしたがって、根本の筐体に記してあるIPアドレスについて、ブラウザからアクセスします。
http://192.168.1.xxx:18333/
手元にあるロボットアームは正常そうということが確認できました。
ROS
まわりのセットアップ
4-1-3. 今回はROSを使います。
公式のリポジトリにしたがってセットアップします。
ROS
を有効にしたあとに、
mkdir -p ~/xarm_ws/src
cd ~/xarm_ws/src
git clone https://github.com/xArm-Developer/xarm_ros --recursive
cd xarm_ros
rosdep update
rosdep install --from-paths . --ignore-src --rosdistro noetic -y
cd ~/xarm_ws
catkin_make
を実行します。これでセットアップは完了です。
Lite6用のREADMEにしたがえば、一応これでROSからロボットアームを動かすことができます。
今回はさらにOpenRRを用いて動かしたいので、もう少し準備が必要です。
4-1-4. OpenRRのセットアップ
OpenRR
をGitHubからクローンし、ビルド、インストールをします。ROS
を使うのでビルドする際にfeatureでROS
を指定します。
git clone https://github.com/openrr/openrr
cd openrr
cargo build --release --features ros
cargo install --path openrr-apps
openrr_apps_robot_teleop
で動かす
4-2.
urdf-viz
のインストール
4-2-0. urdf-vizをまだインストールしていなければインストールしましょう。
cargo install -f urdf-viz
urdf-viz
でシミュレートする
4-2-1. まずurdf-viz上にロボットを表示してシミュレータとして使います。
source ~/xarm_ws/devel/setup.bash
urdf-viz $(rospack find xarm_description)/urdf/lite6_robot.urdf.xacro &
次に関節角度を操作するopenrrのアプリの1つを立ち上げます。
openrr_apps_joint_position_sender
これを実行すると、いくつかのスライドバーがあるウィンドウが現れます。
urdf-viz
に表示し、openrr_apps_joint_position_sender
で動かすにはurdfファイルのみで十分です。コントローラーなどを用いて動かしたい場合やコマンドを割り当てたい場合にはtomlファイルを用意する必要があります。
特定の姿勢に名前をつけておき、実行することも可能です。今回は、Lite6
の公式のソフトウェアにもある初期姿勢をinitial_pose
として登録します。
以下のファイルをlite6_robot_config.toml
として保存してください。
[[urdf_viz_clients_configs]]
name = "lite6"
[openrr_clients_config]
urdf_path = "$(rospack find xarm_description)/urdf/lite6_robot.urdf.xacro"
self_collision_check_pairs = ["joint1:joint4"]
[[openrr_clients_config.ik_clients_configs]]
name = "arm_ik"
client_name = "arm_collision_checked"
solver_name = "arm_ik_solver"
[openrr_clients_config.ik_solvers_configs.arm_ik_solver]
ik_target = "joint_eef"
[[openrr_clients_config.collision_check_clients_configs]]
name = "arm_collision_checked"
client_name = "lite6"
[[openrr_clients_config.joints_poses]]
pose_name = "zero"
client_name = "arm_collision_checked"
positions = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
[[openrr_clients_config.joints_poses]]
pose_name = "initial_pose"
client_name = "arm_collision_checked"
positions = [0.0, 0.35, 1.11, 0.0, 0.76, 0.0]
以下は、openrr_apps_robot_teleop
の設定です。
lite6_teleop_config.toml
として保存してください。
robot_config_path = "lite6_robot_config.toml"
[control_nodes_config]
[control_nodes_config.joints_pose_sender_config]
[[control_nodes_config.ik_node_teleop_configs]]
solver_name = "arm_ik_solver"
joint_trajectory_client_name = "lite6"
[control_nodes_config.ik_node_teleop_configs.config]
mode = "i k"
[[control_nodes_config.joy_joint_teleop_configs]]
client_name = "arm_collision_checked"
[control_nodes_config.joy_joint_teleop_configs.config]
mode = "lite6"
コントローラをパソコンにつないだ上で以下を実行します。
openrr_apps_robot_teleop --config-path lite6_teleop_config.toml
これでコントローラーで画面上(urdf-viz)のロボットアームを操作することができます。
操作方法については、openrr-teleopのjoint_pose_sender
モードの箇所にある通りですが、コントローラーによっては割り当てが違う場合があります。
ROS
で実機を動かす
4-2-2. ROS
を用いてトピックを配信、購読する場合もurdf-viz
のときとおおよそ同様ですが、controller_name
やstate_topic_name
にトピック名を指定する必要があります。
以下をlite6_robot_config_ros.toml
として保存してください。
変更しているのは最初の[[urdf_viz_clients_configs]]
のところを[[ros_clients_configs]]
に変更しているだけです。
[[ros_clients_configs]]
name = "lite6"
joint_names = ["joint1", "joint2", "joint3", "joint4", "joint5", "joint6"]
complete_allowable_errors = [0.02, 0.02, 0.02, 0.02, 0.02, 0.02]
controller_name = "/ufactory/lite6_traj_controller"
state_topic_name = "/ufactory/lite6_traj_controller/state"
[openrr_clients_config]
urdf_path = "$(rospack find xarm_description)/urdf/lite6_robot.urdf.xacro"
self_collision_check_pairs = ["joint1:joint4"]
[[openrr_clients_config.ik_clients_configs]]
name = "arm_ik"
client_name = "arm_collision_checked"
solver_name = "arm_ik_solver"
[openrr_clients_config.ik_solvers_configs.arm_ik_solver]
ik_target = "joint_eef"
[[openrr_clients_config.collision_check_clients_configs]]
name = "arm_collision_checked"
client_name = "lite6"
[[openrr_clients_config.joints_poses]]
pose_name = "zero"
client_name = "arm_collision_checked"
positions = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
[[openrr_clients_config.joints_poses]]
pose_name = "initial_pose"
client_name = "arm_collision_checked"
positions = [0.0, 0.17, 0.56, 0.0, 0.38, 0.0]
lite6_teleop_config.tomlも最初のrobot_config_pathをlite6_robot_config_ros.toml
に書き換えてください。
robot_config_path = "lite6_robot_config_ros.toml"
[control_nodes_config]
[control_nodes_config.joints_pose_sender_config]
[[control_nodes_config.ik_node_teleop_configs]]
solver_name = "arm_ik_solver"
joint_trajectory_client_name = "lite6"
[control_nodes_config.ik_node_teleop_configs.config]
mode = "i k"
[[control_nodes_config.joy_joint_teleop_configs]]
client_name = "arm_collision_checked"
[control_nodes_config.joy_joint_teleop_configs.config]
mode = "lite6"
この2つのファイルを用意したら、ROS
を有効にした上で以下の2つを実行します。
roslaunch lite6_moveit_config realMove_exec.launch robot_ip:=192.168.1.xxx
openrr_apps_robot_teleop --config-path lite6_teleop_config.toml
今度はurdf-viz
ではなく実機のロボットアームが動きます。
ちなみにgazebo
上で動かすこともできます。以下のように実機がない場合でもOpenRR
を用いて動かすことができます。
roslaunch xarm_gazebo lite6_beside_table.launch
openrr_apps_robot_teleop --config-path lite6_teleop_config.toml
openrr-teleop
の機能を使う
4-2-3. このままでもいいのですが、現状だと緊急停止ボタンを押し、解除したあとに再びコントローラーで操作できません。復帰するためのコマンドを割り当てたいと思います。
ExampleのREADMEをみると、初期化のコマンドは
rosservice call /xarm/motion_ctrl 8 1
rosservice call /xarm/set_mode 1
rosservice call /xarm/set_state 0
のようなので、openrr-teleop
からもこのコマンドを実行できるようにします。Lite6
のトピックは/xarm/foo
ではなく、/ufactory/foo
ですから、置換した上で以下のようなテキストファイルを作成します。ファイル名はenable_servo.txt
にしました。
openrr_apps_robot_commands execute_command -- rosservice call /ufactory/motion_ctrl 8 1
openrr_apps_robot_commands execute_command -- rosservice call /ufactory/set_mode 1
openrr_apps_robot_commands execute_command -- rosservice call /ufactory/set_state 0
openrr_apps_robot_command speak Default "Initialization completed!"
また、起動させるためのコマンドを用意したので、停止させるものも追加します。
openrr_apps_robot_commands execute_command -- rosservice call /ufactory/motion_ctrl 8 0
これをstop_servo.txt
として保存します。
さきほどのteleop_config_for_ros.toml
に項目を足して以下のようにします。
robot_config_path = "lite6_robot_config_ros.toml"
[control_nodes_config]
[control_nodes_config.joints_pose_sender_config]
[[control_nodes_config.joy_joint_teleop_configs]]
client_name = "arm_collision_checked"
[control_nodes_config.joy_joint_teleop_configs.config]
mode = "lite6 "
[[control_nodes_config.command_configs]]
name = "stop servo"
file_path = "../command/stop_servo.txt"
[[control_nodes_config.command_configs]]
name = "enable servo"
file_path = "../command/enable_servo.txt"
PrintSpeaker: lite6 0
PrintSpeaker: pose arm_collision_checked zero
PrintSpeaker: commandstop servo
PrintSpeaker: command enable servo
PrintSpeaker: lite6 0
PrintSpeaker: lite6 1
PrintSpeaker: lite6 2
PrintSpeaker: lite6 3
PrintSpeaker: lite6 4
PrintSpeaker: lite6 5
PrintSpeaker: lite6 0
PrintSpeaker: pose arm_collision_checked zero
PrintSpeaker: pose arm_collision_checked initial_pose
PrintSpeaker: pose arm_collision_checked zero
PrintSpeaker: commandstop servo
PrintSpeaker: command enable servo
PrintSpeaker: command stop servo
これで緊急停止ボタンを押して、安全が確認された後でもコントローラーから初期化をして復帰させることができるようになりました。
4−3. 結び
OpenRRを用いてロボットアームを動かすことができました。
今回作成したものは、GitHubのリポジトリにあります。
更新歴
2022-11-01 完成
Discussion