[ros-users] TrajectoryPlannerROS does not take parameter

Patrick Goebel patrick at casbs.stanford.edu
Mon Sep 27 14:44:10 UTC 2010


Hello,

For the past month I have been going through the ROS tutorials and 
trying everything out on my robot (http://www.pirobot.org) which uses a 
Serializer PID controller for the drive wheels and seems to work well 
outside of ROS for moving the robot particular distances at specified 
speeds.

I am now trying to get the navigation stack up and running and I think I 
am 95% of the way there.  The one glitch seems to be similar to what was 
reported by Christian Verbeek on this thread.  Namely, the 
base_local_planner appears to be issuing velocity commands that exceed 
the maximums I have set.  For example, I have max_vel_x set to 0.2, yet 
I am seeing numbers as high as 0.84 on /cmd_vel while simply trying to 
move 1 meter forward.  Similarly, I have max_rotational_vel set to 0.15, 
but I have seen greater values there too.  This is not a rare occurrence 
but happens on almost every nav goal I set in rviz or publish from the 
command line.  Hopefully I am just making a beginner's mistake but I 
have played around with the parameters for two days now and I can't make 
the problem go away.

Here are some of my config files:

base_local_planner_params.yaml:
TrajectoryPlannerROS:
     max_vel_x: 0.2
     min_vel_x: 0.05
     max_rotational_vel: 0.15
     min_in_place_rotational_vel: 0.1
     acc_lim_th: 2.0
     acc_lim_x: 1.0
     acc_lim_y: 1.0
     yaw_goal_tolerance: 0.2
     xy_goal_tolerance: 0.2
     controller_frequency: 5.0
     holonomic_robot: false

cost_common_params.yaml:
obstacle_range: 2.5
raytrace_range: 3.0
footprint: [[-0.13, 0.16], [0.13, 0.16], [0.13, -0.16], [-0.13, -0.16]]
#robot_radius: ir_of_robot
inflation_radius: 0.55
transform_tolerance: 1.0
observation_sources: base_scan
base_scan: {sensor_frame: base_link, data_type: LaserScan, topic: 
base_scan, marking: true, clearing: true

global_costmap_params.yaml:
global_costmap:
     global_frame: map
     robot_base_frame: base_link
     update_frequency: 5.0
     static_map: true
     rolling_window: false

local_costmap_params.yaml:
local_costmap:
     global_frame: odom
     robot_base_frame: base_link
     update_frequency: 5.0
     publish_frequency: 0
     static_map: false
     rolling_window: true
     width: 3.0
     height: 3.0
     resolution: 0.10

My map is simply a white square 500x500 pix at 0.10 resolution.

My move_base.launch file looks like this:
<launch>
<master auto="start"/>

<param name="robot_description" command="cat $(find 
pi_robot)/urdf/pi_robot_urdf.xml" />

<!-- Run the map server -->
<node name="map_server" pkg="map_server" type="map_server" args="$(find 
pi_robot)/blank_map.yaml"/>

<!-- Run Fake Localization -->
<node pkg="fake_localization" type="fake_localization" 
name="fake_localization" output="screen" />

<!-- Create a static transform between the /map frame and /odom -->
<node pkg="tf" type="static_transform_publisher" 
name="odom_map_broadcaster" args="0 0 0 0 0 0 /odom /map 100" />

<node pkg="move_base" type="move_base" respawn="false" name="move_base" 
output="screen">
<param name="controller_frequency" value="5.0" />
<rosparam file="$(find pi_robot)/costmap_common_params.yaml" 
command="load" ns="global_costmap" />
<rosparam file="$(find pi_robot)/costmap_common_params.yaml" 
command="load" ns="local_costmap" />
<rosparam file="$(find pi_robot)/local_costmap_params.yaml" 
command="load" />
<rosparam file="$(find pi_robot)/global_costmap_params.yaml" 
command="load" />
<rosparam file="$(find pi_robot)/base_local_planner_params.yaml" 
command="load" />
</node>
</launch>

I won't have a laser scanner until next month, so I am faking it with 
the following node:

import roslib; roslib.load_manifest('pi_robot')
import rospy
from sensor_msgs.msg import LaserScan
from tf.broadcaster import TransformBroadcaster

rospy.init_node("base_scan")
scanPub = rospy.Publisher('base_scan', LaserScan)
scanBroadcaster = TransformBroadcaster()

scan_rate = 10
rate = rospy.Rate(scan_rate)

rospy.loginfo("Started base scan at " + str(scan_rate) + " Hz")

while not rospy.is_shutdown():

     ranges = list()

     for i in range(30):
         ranges.append(3)

     scan = LaserScan()
     scan.header.stamp = rospy.Time.now()
     scan.header.frame_id = "base_link"
     scan.angle_min = -1.57
     scan.angle_max = 1.57
     scan.angle_increment = 0.108275862
     scan.scan_time = scan_rate
     scan.range_min = 0.5
     scan.range_max = 6.0
     scan.ranges = ranges
     scanPub.publish(scan)

     rate.sleep()


Thanks for your time!

Patrick Goebel




More information about the ros-users mailing list