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

[moveit] create the compute_ik and apply_planning_scene service's args #496

Draft
wants to merge 1 commit into
base: master
Choose a base branch
from
Draft
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 5 additions & 2 deletions pr2eus_moveit/euslisp/robot-moveit.l
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,8 @@
((:query-planner-interface-service qr-pl-srv) "/query_planner_interface")
((:planning-scene-world pl-sc-world) "/planning_scene_world")
((:state-validity-service sv-srv) "/check_state_validity")
((:compute-ik-service cm-ik-srv) "/compute_ik")
((:apply-planning-scene-service ap-ps-srv) "/apply_planning_scene")
((:robot rb)) (frame-id) ;; frame-id needs to be contained in robot_model
((:planner-id pl-id) "RRTConnectkConfigDefault")
(multi-dof-joint-name "virtual_joint")
Expand All @@ -85,6 +87,7 @@
default-planner-id pl-id
multi-dof-name multi-dof-joint-name
multi-dof-frame multi-dof-frame-id)
(instance collision-object-publisher :init :service-name ap-ps-srv :scene-service scene-service)
(ros::advertise planning-scene-world-topic moveit_msgs::PlanningSceneWorld)
(setq default-link (send self :search-link-from-name frame-id))
(setq config-list (send self :default-configuration))
Expand Down Expand Up @@ -199,11 +202,11 @@
:attempts (if attempts attempts 0)
:timeout (ros::time timeout)
:pose_stamped msg)))
(res (ros::service-call "/compute_ik" req)))
(res (ros::service-call cm-ik-srv req)))
(when (and retry (/= (send res :error_code :val) 1))
(send req :ik_request :attempts (if attempts (* 2 attempts) 2))
(send req :ik_request :timeout (ros::time (* 2 timeout)))
(setq res (ros::service-call "/compute_ik" req)))
(setq res (ros::service-call cm-ik-srv req)))
(cond
((= (send res :error_code :val) 1) ;; success
(apply-joint_state (send res :solution :joint_state) robot)) ;; updates joint-list
Expand Down
Loading