On Sun, Nov 21, 2010 at 6:13 PM, Konrad Banachowicz
<konradb3@gmail.com> wrote:
Hi all,
I am trying to set up motion_planning_environment for my manipulator.
I have created my configs basing on these from PR2, everything starts but don't detect collision with environment.
I am running environment_server without collision_map but i create static environment like in this tutorial : http://www.ros.org/wiki/motion_planning_environment/Tutorials/Adding%20known%20objects%20to%20the%20collision%20environment .
I am testing its using code from this tutorial : http://www.ros.org/wiki/motion_planning_environment/Tutorials/Tutorial%20A
My configs in appendix, all other configs for my manipulator can be found in my github repo : https://github.com/RCPRG-ros-pkg/irp6_robot .
Hi Konrad,
In the attached files, it seems that you are not specifying the self-collision checks to be performed (the default is none). In $(find irp6_test)/config/collision_checks_both_arms.yaml you have commented-out the line that includes the relevant file (which AFAICT does not exist yet). Without a collision map or self-collision geometries, there is nothing to collide with!. Relevant code pasted below:
<launch>
<!-- send parameters for collision checking for PR2; this includes parameters for the self filter -->
<!-- <rosparam command="load" ns="robot_description_collision" file="$(find irp6_test)/config/collision_checks_both_arms.yaml" />
-->
<!-- send parameters needed for motion planning -->
<rosparam command="load" ns="robot_description_planning" file="$(find irp_test)/config/planning_groups.yaml" />
</launch>
Also, you should probably define additional groups in $(find irp_test)/config/planning_groups.yaml, which can be links-only (no joints needed here) which specify self-collision geometry groups, e.g.,
In $(find irp_test)/config/planning_groups.yaml:
- name: selfcol1
links:
link1
link2
base_link
- name: selfcol2
links:
link6
In $(find irp6_test)/config/collision_checks_both_arms.yaml
default_collision_operations:
- object1: selfcol1
object2: selfcol2
operation: enable # Enable collision checks between link6 and {base_link, link1, link2}
HTH,
Adolfo.
Thanks for your help,
Konrad Bnanachowicz
_______________________________________________
ros-users mailing list
ros-users@code.ros.org
https://code.ros.org/mailman/listinfo/ros-users