[ros-users] Problems in running navigation stack

Eitan Marder-Eppstein eitan at willowgarage.com
Fri Apr 16 17:15:00 UTC 2010


Hitesh,

I'm not sure that I completely understand what you're saying. You can give
the navigation stack a goal in any frame you want. For example, if I want
the base to move forward 1 meter, I'd give a goal in the "base_link" frame 1
meter ahead of the robot.

Hope this helps,

Eitan

On Thu, Apr 15, 2010 at 10:29 PM, hitesh dhiman <
hitesh.dhiman.1988 at gmail.com> wrote:

> Hi Eitan,
> Thanks for the help, I'm finally getting velocity commands out. Relating to
> the application of the navigation stack for my project, i have some doubts.
> The navigation stack requires a goal in order to move. My question is, if I
> want to traverse an unknown environment that has obstacles: an office
> corridor, for example, i can pass a goal with 1m forward..but if there is a
> turn in the path, the robot will not be able to turn accordingly since the
> goal represents a position in the global world.
> Therefore, using the simple navigation goal will not suffice in the current
> scenario. Is it possible to give the robot goal commands in the local
> system?
>
> On Thu, Apr 15, 2010 at 1:06 AM, Eitan Marder-Eppstein <
> eitan at willowgarage.com> wrote:
>
>> Hitesh,
>>
>> First off, it seems like something might be weird with your laser scans.
>> You need to make sure of two things:
>>
>> 1) That the header in the laser messages sent out contain the correct
>> frame_id and timestamp for tf to be able to use them.
>> 2) That the transform betweeen odom and [your_laser_frame_name] exists in
>> your tf tree. You can "rosrun tf view_frames" to generate a pdf of your tf
>> tree which you can check.
>>
>> To verify that things are working, try to view laser scans in rviz with
>> both fixed and target frame set to odom. If you see them show up... things
>> are good.
>>
>> Next, to use the navigation stack in the odometric frame, you'll have to
>> change some of the parameters in the global_costmap_params.yaml file to tell
>> it that you want it to operate in an odometric frame rather than using a
>> static map. Something like the following configuration should work:
>>
>> global_costmap:
>>   global_frame: odom
>>   robot_base_frame: base_link
>>   update_frequency: 5.0
>>   publish_frequency: 0.0
>>   static_map: false
>>   rolling_window: true
>>
>>
>>
>>   width: 20.0
>>   height: 20.0
>>   resolution: 0.05
>>
>> This will give you a 20m x 20m around the robot in which you can send
>> goals in the odometric frame.
>>
>> Hope this helps a bit,
>>
>> Eitan
>>
>>
>> On Wed, Apr 14, 2010 at 6:48 AM, hitesh dhiman <
>> hitesh.dhiman.1988 at gmail.com> wrote:
>>
>>> Hi,
>>> actually i did use the tutorial to configure the robot. My setup is
>>> almost the same as the files listed in the tutorial, except that the costmap
>>> configuration is set to a differential robot.
>>> From what i could see using rxgraph, i'm getting the following messages
>>> into move_base:
>>>
>>> 1) Odometry
>>> 2) Odometry tf
>>> 3) laser tf (base_link to base_laser)
>>> 4) laserscan
>>>
>>> I'm not using a static map, so I removd amcl from move_base.launch.
>>> When i start the move_base.launch file, i get the following:
>>>
>>> [ INFO] 1271252548.078700000: Subscribed to Topics: laser_scan_sensor
>>> [ INFO] 1271252548.178918000: MAP SIZE: 199, 199
>>> [ INFO] 1271252548.185354000: Subscribed to Topics: laser_scan_sensor
>>> [ WARN] 1271252563.370080000: MessageNotifier [topic=scan,
>>> target=/base_laser /base_laser ]: Dropped 100.00% of messages so far. Please
>>> turn the [ros.costmap_2d.message_notifier] rosconsole logger to DEBUG for
>>> more information.
>>>
>>> Using rxloggerlevel to debug, here's the output:
>>>
>>> [DEBUG] 1271251959.320831000: MessageNotifier [topic=scan, target=/odom
>>> /base_laser ]: Added message in frame laser at time 1271251959.264, count
>>> now 50
>>> [DEBUG] 1271251959.320973000: MessageNotifier [topic=scan, target=/odom
>>> /base_laser ]: Removed oldest message because buffer is full, count now 50
>>> (frame_id=laser, stamp=1271251958.043920)
>>>
>>>  [DEBUG] 1271251959.599588000: MessageNotifier [topic=scan,
>>> target=/base_laser /base_laser ]: Successful Transforms: 0, Failed
>>> Transforms: 4051196, Discarded due to age: 0, Transform messages received:
>>> 67611, Messages received: 26918, Total dropped: 26868
>>>
>>> Also, to view the laser scan image in rviz, i get the following error:
>>>
>>> TOPIC : No messages received
>>> Transform[sender=/laser] : For frame [laser]: Frame [laser] does not
>>> exist
>>>
>>>
>>> Any suggestions?
>>>
>>> On Wed, Apr 14, 2010 at 1:01 AM, Eitan Marder-Eppstein <
>>> eitan at willowgarage.com> wrote:
>>>
>>>> Hitesh,
>>>>
>>>> If you're trying to run the navigation stack on your own robot, I'd
>>>> suggest reading the following tutorial first,
>>>> http://www.ros.org/wiki/navigation/Tutorials/RobotSetup/, as it will
>>>> explain how the pieces of the navigation stack work and how you'll need to
>>>> configure your robot.
>>>>
>>>> From the errors you listed, it looks like your robot may not be
>>>> publishing odometry information to the navigation stack. Also, amcl will not
>>>> work without a static map... so that's expected.
>>>>
>>>> Hopefully, the tutorial will help, feel free to post again if you have
>>>> other questions,
>>>>
>>>> Eitan
>>>>
>>>> On Tue, Apr 13, 2010 at 5:49 AM, hitesh dhiman <
>>>> hitesh.dhiman.1988 at gmail.com> wrote:
>>>>
>>>>> Hi all,
>>>>> I've been trying to run the navigation stack. However, upon running
>>>>> move_base.launch, i get the following message:
>>>>>
>>>>> [ WARN] 1271162502.543875000: Costmap2DROS transform timeout. Current
>>>>> time: 1271162502.5438, global_pose stamp: 1271162501.8677, tolerance: 0.3000
>>>>>
>>>>> I tried changing the tolerance value to 1. move_base.launch starts with
>>>>> the following:
>>>>> [ INFO] 1271162733.968657000: Subscribed to Topics: laser_scan_sensor
>>>>> [ INFO] 1271162734.066727000: MAP SIZE: 199, 199
>>>>>
>>>>> A second later, i start getting these messages:
>>>>>
>>>>> [ WARN] 1271162749.245438000: MessageNotifier [topic=scan, target=/odom
>>>>> /base_laser ]: Dropped 100.00% of messages so far. Please turn the
>>>>> [ros.costmap_2d.message_notifier] rosconsole logger to DEBUG for more
>>>>> information.
>>>>>
>>>>> rxconsole gives the following:
>>>>> Request for map failed, trying again...  Warn /amcl
>>>>> This could be because i'm not using any static map. Even so, move_base
>>>>> is not publishing any messages out.
>>>>>
>>>>> Any help would be appreciated. I'm not able to figure out where the
>>>>> problem is.
>>>>>
>>>>> --
>>>>> Regards,
>>>>> Hitesh Dhiman
>>>>> Electrical Engineering
>>>>> National University of Singapore
>>>>>
>>>>>
>>>>> ------------------------------------------------------------------------------
>>>>> Download Intel® Parallel Studio Eval
>>>>> Try the new software tools for yourself. Speed compiling, find bugs
>>>>> proactively, and fine-tune applications for parallel performance.
>>>>> See why Intel Parallel Studio got high marks during beta.
>>>>> http://p.sf.net/sfu/intel-sw-dev
>>>>> _______________________________________________
>>>>> ros-users mailing list
>>>>> ros-users at lists.sourceforge.net
>>>>> https://lists.sourceforge.net/lists/listinfo/ros-users
>>>>>
>>>>> _______________________________________________
>>>>> ros-users mailing list
>>>>> ros-users at code.ros.org
>>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>>
>>>>>
>>>>
>>>> _______________________________________________
>>>> ros-users mailing list
>>>> ros-users at code.ros.org
>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>
>>>>
>>>
>>>
>>> --
>>> Regards,
>>> Hitesh Dhiman
>>> Electrical Engineering
>>> National University of Singapore
>>>
>>> _______________________________________________
>>> ros-users mailing list
>>> ros-users at code.ros.org
>>> https://code.ros.org/mailman/listinfo/ros-users
>>>
>>>
>>
>> _______________________________________________
>> ros-users mailing list
>> ros-users at code.ros.org
>> https://code.ros.org/mailman/listinfo/ros-users
>>
>>
>
>
> --
> Regards,
> Hitesh Dhiman
> Electrical Engineering
> National University of Singapore
>
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20100416/37a5c0d2/attachment-0003.html>


More information about the ros-users mailing list