Re: [ros-users] motion_planning_environment set up.

Top Page
Attachments:
Message as email
+ (text/plain)
+ (text/html)
+ gdb.log (text/x-log)
Delete this message
Reply to this message
Author: User discussions
Date:  
To: User discussions
Subject: Re: [ros-users] motion_planning_environment set up.
I have done some more test and I found that if default_collision_operations is
empty environment_server does not check for any collisions.
I think it's a bug and environment_server should check collisions by
default.
Second problem is when environment_server does not received collision_map or
received empty collision_map every request on environment_server which
require collision checking ends with segmentation fault. GDB output in
appendix.

Pozdrawiam
Konrad Banachowicz


2010/11/23 Adolfo Rodríguez Tsouroukdissian <
>

>
>
> On Mon, Nov 22, 2010 at 10:12 PM, Konrad Banachowicz <>wrote:
>
>> 2010/11/22 Adolfo Rodríguez Tsouroukdissian <
>> >
>>
>>>
>>>
>>> On Sun, Nov 21, 2010 at 6:13 PM, Konrad Banachowicz <>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!.
>>>
>> Self collision is useless for me because my manipulator is not able to
>> self collide.
>> But i am adding "known objects" like in this tutorial :
>> http://www.ros.org/wiki/motion_planning_environment/Tutorials/Adding%20known%20objects%20to%20the%20collision%20environment.
>> Whether it is taken into account by environment_server ?
>>
>
> Oh yes, I misunderstood your post. Can't help you much there, for I haven't
> used static collision objects yet. All I can think of now is to check
> whether the "collision_object" topic is being published correctly, and that
> it is correctly connected to your planning environment node.
>
> Adolfo.
>
>
>
> --
> Adolfo Rodríguez Tsouroukdissian, Ph. D.
>
> Robotics engineer
> PAL ROBOTICS S.L
> http://www.pal-robotics.com
> Tel. +34.93.414.53.47
> Fax.+34.93.209.11.09
>
> CONFIDENTIALITY NOTICE: This e-mail and the accompanying document(s) may
> contain confidential information which is privileged and intended only for
> the individual or entity to whom they are addressed. If you are not the
> intended recipient, you are hereby notified that any disclosure, copying,
> distribution or use of this e-mail and/or accompanying document(s) is
> strictly prohibited. If you have received this e-mail in error, please
> immediately notify the sender at the above e-mail address.
>
> _______________________________________________
> ros-users mailing list
>
> https://code.ros.org/mailman/listinfo/ros-users
>
>

GNU gdb (GDB) 7.1-ubuntu
Copyright (C) 2010 Free Software Foundation, Inc.
License GPLv3+: GNU GPL version 3 or later <http://gnu.org/licenses/gpl.html>
This is free software: you are free to change and redistribute it.
There is NO WARRANTY, to the extent permitted by law. Type "show copying"
and "show warranty" for details.
This GDB was configured as "x86_64-linux-gnu".
For bug reporting instructions, please see:
<http://www.gnu.org/software/gdb/bugs/>...
Reading symbols from /opt/ros/cturtle/stacks/motion_planning_environment/planning_environment/bin/environment_server...
done.
(gdb)
(gdb) r
Starting program: /opt/ros/cturtle/stacks/motion_planning_environment/planning_environment/bin/environment_server collision_map:=collision_map_occ collision_map_update:=collision_map_occ_update __name:=environment_server_irp6p __log:=/home/konrad/.ros/log/590d9922-fc9b-11df-a8f2-485b397ce758/environment_server_irp6p-4.log
[Thread debugging using libthread_db enabled]
[New Thread 0x7fffec4ff700 (LWP 16604)]
[New Thread 0x7fffebcfe700 (LWP 16605)]
[New Thread 0x7fffeb4fd700 (LWP 16606)]
[New Thread 0x7fffeacfc700 (LWP 16612)]
[New Thread 0x7fffea4fb700 (LWP 16615)]
[ERROR] [1291133039.818123534]: Link 'world' not found
[ INFO] [1291133039.819109623]: Robot frame is 'base_link'
[New Thread 0x7fffe9cfa700 (LWP 16641)]
[ INFO] [1291133039.893404610]: Configuring server for 'irp6p'
[ INFO] [1291133039.893571810]: Waiting for robot state ...
[ INFO] [1291133039.893619232]: Waiting for joint state ...
[ INFO] [1291133039.893664699]: Pose ignored
[ INFO] [1291133039.944128304]: Robot state received!
[ INFO] [1291133039.944374215]: Waiting for map ...
[ WARN] [1291133039.995952976]: Message from [/rostopic_15992_1291133028501] has a non-fully-qualified frame_id [world]. Resolved locally to [/world]. This is will likely not work in multi-robot systems. This message will only print once.
[ INFO] [1291133041.964434026]: Waiting for map ...
[ INFO] [1291133043.979803926]: Waiting for map ...
[ INFO] [1291133046.008292184]: Waiting for map ...
[ INFO] [1291133048.028455151]: Waiting for map ...
[ INFO] [1291133050.051030784]: Waiting for map ...
[ INFO] [1291133052.071739352]: Waiting for map ...
[ INFO] [1291133054.088541208]: Waiting for map ...
[ WARN] [1291133054.897183093]: MessageFilter [target=/base_link ]: Dropped 100.00% of messages so far. Please turn the [ros.planning_environment.message_notifier] rosconsole logger to DEBUG for more information.
[ WARN] [1291133054.897435848]: MessageFilter [target=/base_link ]: The majority of dropped messages were due to messages growing older than the TF cache time. The last message's timestamp was: 1291133028.645655, and the last frame_id was: /world
[ INFO] [1291133056.107494176]: Waiting for map ...
[New Thread 0x7fffe94f9700 (LWP 17519)]
[ INFO] [1291133058.123552433]: Waiting for map ...
[ INFO] [1291133060.137874155]: Waiting for map ...
[ INFO] [1291133062.052390175]: Map received!
[ INFO] [1291133062.195966596]: Environment server started

Program received signal SIGSEGV, Segmentation fault.
0x00007ffff3a3479c in std::_Bit_reference::operator= (
    this=<value optimized out>, ord=<value optimized out>, curAllowed=..., 
    vecIndices=<value optimized out>)
    at /usr/include/c++/4.4/bits/stl_bvector.h:84
84              *_M_p |= _M_mask;
(gdb) bt
#0  0x00007ffff3a3479c in std::_Bit_reference::operator= (
    this=<value optimized out>, ord=<value optimized out>, curAllowed=..., 
    vecIndices=<value optimized out>)
    at /usr/include/c++/4.4/bits/stl_bvector.h:84
#1  planning_environment::CollisionSpaceMonitor::applyOrderedCollisionOperationsToMatrix (this=<value optimized out>, ord=<value optimized out>, 
    curAllowed=..., vecIndices=<value optimized out>)
    at /tmp/buildd/ros-cturtle-motion-planning-environment-0.2.3/debian/ros-cturtle-motion-planning-environment/opt/ros/cturtle/stacks/motion_planning_environment/planning_environment/src/monitors/collision_space_monitor.cpp:977
#2  0x00007ffff3a3cede in planning_environment::CollisionSpaceMonitor::applyOrderedCollisionOperationsToCollisionSpace (this=0x6e2ad0, 
    ord=<value optimized out>, print=false)
    at /tmp/buildd/ros-cturtle-motion-planning-environment-0.2.3/debian/ros-cturtle-motion-planning-environment/opt/ros/cturtle/stacks/motion_planning_environment/planning_environment/src/monitors/collision_space_monitor.cpp:918
#3  0x0000000000448a41 in planning_environment::EnvironmentServer::getStateValidity (this=0x7fffffffd280, req=<value optimized out>, res=<value optimized out>)
    at /tmp/buildd/ros-cturtle-motion-planning-environment-0.2.3/debian/ros-cturtle-motion-planning-environment/opt/ros/cturtle/stacks/motion_planning_environment/planning_environment/src/monitors/environment_server.cpp:310
#4  0x0000000000455c29 in boost::function2<bool, planning_environment_msgs::GetStateValidityRequest_<std::allocator<void> >&, planning_environment_msgs::GetStat---Type <return> to continue, or q <return> to quit---
eValidityResponse_<std::allocator<void> >&>::operator() (this=0x70d430, 
    params=...) at /usr/include/boost/function/function_template.hpp:1013
#5  ros::ServiceSpec<planning_environment_msgs::GetStateValidityRequest_<std::allocator<void> >, planning_environment_msgs::GetStateValidityResponse_<std::allocator<void> > >::call(boost::function<bool ()(planning_environment_msgs::GetStateValidityRequest_<std::allocator<void> >&, planning_environment_msgs::GetStateValidityResponse_<std::allocator<void> >&)> const&, ros::ServiceSpecCallParams<planning_environment_msgs::GetStateValidityRequest_<std::allocator<void> >, planning_environment_msgs::GetStateValidityResponse_<std::allocator<void> > >&) (
    this=0x70d430, params=...)
    at /opt/ros/cturtle/ros/core/roscpp/include/ros/service_callback_helper.h:136
#6  ros::ServiceCallbackHelperT<ros::ServiceSpec<planning_environment_msgs::GetStateValidityRequest_<std::allocator<void> >, planning_environment_msgs::GetStateValidityResponse_<std::allocator<void> > > >::call (this=0x70d430, params=...)
    at /opt/ros/cturtle/ros/core/roscpp/include/ros/service_callback_helper.h:188
#7  0x00007ffff506e428 in ros::ServiceCallback::call (this=0x74d040)
    at /tmp/buildd/ros-cturtle-ros-1.2.4/debian/ros-cturtle-ros/opt/ros/cturtle/ros/core/roscpp/src/libros/service_publication.cpp:123
#8  0x00007ffff50805d1 in ros::CallbackQueue::callOneCB (this=0x6b8bc0, 
    tls=0x7fffe400cbd0)
    at /tmp/buildd/ros-cturtle-ros-1.2.4/debian/ros-cturtle-ros/opt/ros/cturtle/---Type <return> to continue, or q <return> to quit---
ros/core/roscpp/src/libros/callback_queue.cpp:381
#9  0x00007ffff50816cb in ros::CallbackQueue::callAvailable (this=0x6b8bc0, 
    timeout=<value optimized out>)
    at /tmp/buildd/ros-cturtle-ros-1.2.4/debian/ros-cturtle-ros/opt/ros/cturtle/ros/core/roscpp/src/libros/callback_queue.cpp:333
#10 0x00007ffff5086aa9 in ros::SingleThreadedSpinner::spin (
    this=<value optimized out>, queue=0x6b8bc0)
    at /tmp/buildd/ros-cturtle-ros-1.2.4/debian/ros-cturtle-ros/opt/ros/cturtle/ros/core/roscpp/src/libros/spinner.cpp:49
#11 0x00007ffff500fa5b in ros::spin ()
    at /tmp/buildd/ros-cturtle-ros-1.2.4/debian/ros-cturtle-ros/opt/ros/cturtle/ros/core/roscpp/src/libros/init.cpp:488
#12 0x000000000042bdc6 in main (argc=1, argv=<value optimized out>)
    at /tmp/buildd/ros-cturtle-motion-planning-environment-0.2.3/debian/ros-cturtle-motion-planning-environment/opt/ros/cturtle/stacks/motion_planning_environment/planning_environment/src/monitors/environment_server.cpp:595
(gdb)