Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ローカルでも実機と同じように干渉回避するにはどのようにしたら良いのでしょうか. #1307

Open
k-okada opened this issue Dec 17, 2020 · 2 comments

Comments

@k-okada
Copy link
Member

k-okada commented Dec 17, 2020

@ketaro-m

ドアやubereatsボックスを衝突回避しようとしてcollision objectを追加した状態で腕を動かしているのですが,ローカルで試した場合と実機で動かした場合で腕の動きが異なります.おそらくはローカルで動かした場合は干渉回避が正しく行われておらずcollision objectを追加しない状態と同じ動きをするのですが,実機の場合は正しく干渉回避をするので,別の動きになってしまうのだと思います.
ローカルでも実機と同じように干渉回避するにはどのようにしたら良いのでしょうか.

ちなみに,ローカルで試す場合は下のlaunchファイルを立ち上げてからcollision objectを追加しています.

$ roslaunch fetch_moveit_config demo.launch

@yuli-disney, @softyanija, @tenrobo18, @tkmtnt7000, @tkmtnt7000

jsk-ros-pkg/jsk_demos#1309 (comment)

@k-okada
Copy link
Member Author

k-okada commented Dec 17, 2020

1)一番確実なのはgazeboを実行してからmoveitを動かしてすすめることです.
それぞれ別のターミナルで以下を起ち上げてください.

$ roslaunch fetch_gazebo playground.launch 
$ roslaunch fetch_moveit_config move_group.launch 
$ roslaunch moveit_rviz.launch config:=true

これで基本は実機と同じ構成になります.あとはroseusを起ち上げて以下のプログラムを実行します.

(load "package://fetcheus/fetch-interface.l")
(if (not (boundp '*ri*))
    (fetch-init))

(setq *door-collision-model* (make-cube 10 1000 2000 :pos #f(600 0 1000)))
(objects (list *fetch* *door-collision-model*))
(when (boundp '*co*)
  (send *co* :add-object *door-collision-model* :frame-id "base_link" :object-id "door"))

;; reset-pose                                                                                                                
(send *fetch* :angle-vector #f(0 90 0 0 0 0 0 0 0 0))
(send *ri* :angle-vector (send *fetch* :angle-vector))
(send *ri* :wait-interpolation)

;; reach-pose                                                                                                                
(send *fetch* :rarm :inverse-kinematics (make-coords :pos #f(500 0 1200) :rpy (float-vector -pi/2 0 pi/2)))
(send *ri* :angle-vector (send *fetch* :angle-vector))
(send *ri* :wait-interpolation)

するとちゃんと障害物を避けている事がわかります.

gazebo
moveit

2)gazeboは重くなるのでmoveitだけ使いたい場合ですが,こんどはdemo.launchを起ち上げた後,/joint_state_publisherを止めます.

$ roslaunch fetch_moveit_config demo.launch
$ rosnode kill /joint_state_publisher

あとはroseusを起ち上げて上と同じプログラムを実行すると,
moveit-fail

と壁をすり抜けてしまいます(困っているのはこの状況でしょうか?こういう風に何をどうして,どうなって,その何が困っているか,と書けるように成ると良いです)

で,その場合ですが:angle-vectorの代わりに

(send *ri* :angle-vector-motion-plan (send *fetch* :angle-vector) :move-arm :rarm)

とすると
moveit-ok
のようになりますが,これで期待通りでしょうか?

ちなみに実機でもmoveitが存在する場合でも同じコードを動かすためには
#1306 を使うと良いです.

@ketaro-m
Copy link

ご丁寧にお返事ありがとうございます.今日ラボに行く予定なので,実機とともに試してみたいと思います.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants