|
From: <ei...@us...> - 2009-06-29 21:31:24
|
Revision: 17895
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17895&view=rev
Author: eitanme
Date: 2009-06-29 21:30:21 +0000 (Mon, 29 Jun 2009)
Log Message:
-----------
Fixing a spelling error with one of the Cosmap2DROS parameters. Also, adding documentation for the costmap_2d_tutorials package.
Modified Paths:
--------------
pkg/trunk/demos/2dnav_erratic/config/costmap_common_params.yaml
pkg/trunk/demos/2dnav_pr2/config/costmap_common_params.yaml
pkg/trunk/demos/door_demos/launch/move_base_door.launch
pkg/trunk/demos/erratic_gazebo/costmap_common_params.yaml
pkg/trunk/highlevel/move_base_stage/config/costmap_common_params.yaml
pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/sbpl_door_action_planner.launch
pkg/trunk/nav/base_local_planner/mainpage.dox
pkg/trunk/nav/nav_apps/costmap_2d_tutorials/launch_example/costmap_params.yaml
pkg/trunk/nav/nav_apps/costmap_2d_tutorials/mainpage.dox
pkg/trunk/stacks/world_models/costmap_2d/include/costmap_2d/observation_buffer.h
pkg/trunk/stacks/world_models/costmap_2d/launch_costmap_2d_ros.xml
pkg/trunk/stacks/world_models/costmap_2d/mainpage.dox
pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp
Modified: pkg/trunk/demos/2dnav_erratic/config/costmap_common_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_erratic/config/costmap_common_params.yaml 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/demos/2dnav_erratic/config/costmap_common_params.yaml 2009-06-29 21:30:21 UTC (rev 17895)
@@ -17,4 +17,4 @@
lethal_cost_threshold: 100
observation_topics: scan
scan: {sensor_frame: frame_from_message, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}
+ observation_persistence: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}
Modified: pkg/trunk/demos/2dnav_pr2/config/costmap_common_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/config/costmap_common_params.yaml 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/demos/2dnav_pr2/config/costmap_common_params.yaml 2009-06-29 21:30:21 UTC (rev 17895)
@@ -19,14 +19,14 @@
observation_topics: base_scan_marking base_scan tilt_scan ground_object_cloud
base_scan_marking: {sensor_frame: base_laser, data_type: PointCloud, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstacle_height: 2.0}
+ observation_persistence: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstacle_height: 2.0}
base_scan: {sensor_frame: base_laser, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: false, clearing: true, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
+ observation_persistence: 0.0, marking: false, clearing: true, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
tilt_scan: {sensor_frame: laser_tilt_link, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.2, marking: false, clearing: true, min_obstacle_height: -20.00, max_obstacle_height: 40.0}
+ observation_persistence: 0.2, marking: false, clearing: true, min_obstacle_height: -20.00, max_obstacle_height: 40.0}
ground_object_cloud: {sensor_frame: laser_tilt_link, data_type: PointCloud, expected_update_rate: 0.2,
- observation_persistance: 3.0, marking: true, clearing: false, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
+ observation_persistence: 3.0, marking: true, clearing: false, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
# END VOXEL STUFF
Modified: pkg/trunk/demos/door_demos/launch/move_base_door.launch
===================================================================
--- pkg/trunk/demos/door_demos/launch/move_base_door.launch 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/demos/door_demos/launch/move_base_door.launch 2009-06-29 21:30:21 UTC (rev 17895)
@@ -35,21 +35,21 @@
<param name="costmap/observation_topics" value="base_scan base_scan_marking" />
<param name="costmap/base_scan/sensor_frame" value="frame_from_message" />
- <param name="costmap/base_scan/observation_persistance" value="0.0" />
+ <param name="costmap/base_scan/observation_persistence" value="0.0" />
<param name="costmap/base_scan/expected_update_rate" value="0.2" />
<param name="costmap/base_scan/data_type" value="LaserScan" />
<param name="costmap/base_scan/clearing" value="true" />
<param name="costmap/base_scan/marking" value="false" />
<param name="costmap/base_scan_marking/sensor_frame" value="frame_from_message" />
- <param name="costmap/base_scan_marking/observation_persistance" value="0.0" />
+ <param name="costmap/base_scan_marking/observation_persistence" value="0.0" />
<param name="costmap/base_scan_marking/expected_update_rate" value="0.2" />
<param name="costmap/base_scan_marking/data_type" value="PointCloud" />
<param name="costmap/base_scan_marking/clearing" value="false" />
<param name="costmap/base_scan_marking/marking" value="true" />
<param name="costmap/tilt_scan/sensor_frame" value="frame_from_message" />
- <param name="costmap/tilt_scan/observation_persistance" value="0.0" />
+ <param name="costmap/tilt_scan/observation_persistence" value="0.0" />
<param name="costmap/tilt_scan/expected_update_rate" value="0.2" />
<param name="costmap/tilt_scan/data_type" value="LaserScan" />
<param name="costmap/tilt_scan/clearing" value="true" />
Modified: pkg/trunk/demos/erratic_gazebo/costmap_common_params.yaml
===================================================================
--- pkg/trunk/demos/erratic_gazebo/costmap_common_params.yaml 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/demos/erratic_gazebo/costmap_common_params.yaml 2009-06-29 21:30:21 UTC (rev 17895)
@@ -12,7 +12,7 @@
observation_topics: base_scan_marking base_scan
base_scan_marking: {sensor_frame: base_laser, data_type: PointCloud, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstalce_height: 2.0}
+ observation_persistence: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstalce_height: 2.0}
base_scan: {sensor_frame: base_laser, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: false, clearing: true, min_obstacle_height: 0.08, max_obstalce_height: 2.0}
+ observation_persistence: 0.0, marking: false, clearing: true, min_obstacle_height: 0.08, max_obstalce_height: 2.0}
Modified: pkg/trunk/highlevel/move_base_stage/config/costmap_common_params.yaml
===================================================================
--- pkg/trunk/highlevel/move_base_stage/config/costmap_common_params.yaml 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/highlevel/move_base_stage/config/costmap_common_params.yaml 2009-06-29 21:30:21 UTC (rev 17895)
@@ -17,4 +17,4 @@
lethal_cost_threshold: 100
observation_topics: base_scan
base_scan: {sensor_frame: frame_from_message, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}
+ observation_persistence: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}
Modified: pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/sbpl_door_action_planner.launch
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/sbpl_door_action_planner.launch 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/sbpl_door_action_planner.launch 2009-06-29 21:30:21 UTC (rev 17895)
@@ -18,7 +18,7 @@
<param name="costmap/observation_topics" value="base_scan" />
<param name="costmap/base_scan/sensor_frame" value="frame_from_message" />
- <param name="costmap/base_scan/observation_persistance" value="0.0" />
+ <param name="costmap/base_scan/observation_persistence" value="0.0" />
<param name="costmap/base_scan/expected_update_rate" value="0.2" />
<param name="costmap/base_scan/data_type" value="LaserScan" />
<param name="costmap/base_scan/clearing" value="true" />
Modified: pkg/trunk/nav/base_local_planner/mainpage.dox
===================================================================
--- pkg/trunk/nav/base_local_planner/mainpage.dox 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/nav/base_local_planner/mainpage.dox 2009-06-29 21:30:21 UTC (rev 17895)
@@ -4,10 +4,25 @@
@htmlinclude manifest.html
@section summary Summary
-Write a summary here
+This package provides an implementation of a local planner for a mobile robot.
+The planner uses either the Trajectory Rollout or Dynamic Window Approach to povide safe local naivagtion
+commands to the base.
-@subsection example Example
-An example of a subsection
+@section usage Usage
+There are two main ways to use this package. The first is to create a TrajectoryPlanner object and manage it
+yourself. The second, and encouraged method, is to use a ROS wrapper (base_local_planner::TrajectoryPlannerROS)
+that manages the underlying TrajectoryPlanner for you and adheres to the ROS nav_robot_actions::BaseLocalPlanner
+interface. See below for an example of base_local_planner::TrajectoryPlannerROS construction.
+@subsection construction TrajectoryPlannerROS Construction
+To construct a base_local_planner::TrajectoryPlannerROS object, pass it a name, a reference to a
+costmap_2D::Costmap2DROS, and a reference to a tf::TransformListener.
+@verbatim
+#include "ros/ros.h"
+#include "tf/transform_listener.h"
+#include "costmap_2d/costmap_2d_ros.h"
+#include "base_local_planner/trajectory_planner_ros.h"
+
+
*/
Modified: pkg/trunk/nav/nav_apps/costmap_2d_tutorials/launch_example/costmap_params.yaml
===================================================================
--- pkg/trunk/nav/nav_apps/costmap_2d_tutorials/launch_example/costmap_params.yaml 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/nav/nav_apps/costmap_2d_tutorials/launch_example/costmap_params.yaml 2009-06-29 21:30:21 UTC (rev 17895)
@@ -1,24 +1,116 @@
+#First, we need to set frame_ids for the costmap. The global_frame refers to the
+#operating frame of the costmap, and the robot_base_frame refers to the frame of
+#the base link of the robot. Here, we'll set them to "map" and "base_link"
+#respectively.
global_frame: /map
robot_base_frame: base_link
+
+#Next, we'll set the some frequency parameters for the costmap. The first is the
+#update_frequency. This controls how often sensor data from the world should bet
+#put into the costmap. The higher this parameter is set, the more current the
+#costmap's world will be. However, keep in mind that with more frequent updates
+#also comes more CPU usage. We'll use a value of 5Hz as our update rate. The
+#second frequency parameter that we can set on the costmap is how often to
+#publish visualization data. We'll set that to 2Hz.
update_frequency: 5.0
publish_frequency: 2.0
+
+#The transform_tolerance parameter is used to define the latency we are willing to accept
+#on transforms from the robot_base_frame to the global_frame of the costmap. We'll set this
+#to 0.3 seconds.
transform_tolerance: 0.3
+
+#The obstacle_range parameter defines at what distance we will start to use sensor data
+#to place obstacles into the costmap. We'll set it to 2.5 meters here which means that we'll
+#put in sensor hits that are up to 2.5 meters away from us.
obstacle_range: 2.5
+
+#The max_obstacle_height parameter defines the maximum height of an obstacle for the costmap.
+#We'll set it to 2.0 meters for our robot.
max_obstacle_height: 2.0
+
+#The raytrace_range parameter sets how far we'll look out from the robot when raytracing freeespace.
+#Here we'll set it to be 3.0 meters. Its suggested to set this parameter to be equal or greater to
+#the obstacle_range parameter above to ensure that freespace is cleared out correctly.
raytrace_range: 3.0
+
+#The following three parameters are used for inflation of obstacles within the costmap. The inscribed
+#radius should be set to the radius of the inner circle of the robot. The circumscribed radius should
+#be set to the radius of the outer circle of the robot. The inflation radius should be set to the maximum
+#distance from obstacles at which cost information is desired.
inscribed_radius: 0.325
circumscribed_radius: 0.46
inflation_radius: 0.55
+#The observation_topics list allows users of a Costmap2DROS object to specify what topics should be used
+#in conjunction with the underlying Costmap2D object. Topics should be listed here, separated by spaces and
+#should be configured in their individual namespaces as shown below. Each topic in this list will be subscribed
+#to and managed by the Costmap2DROS object subject to its configuration settings.
observation_topics: base_scan
-base_scan: {sensor_frame: frame_from_message, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}
+#This is an example of topic configuration for the base_scan topic listed in the observation_topics list above.
+#Notice that the base scan receives its own namespace to read its configuration from.
+base_scan:
+#The sensor_frame parameter specifies what frame the origin of the sensor is
+#assumed to be in. The special value "frame_from_message" infers the origin
+#frame from the frame_id sent in each message over the base_scan topic. Any
+#other string will override the frame_id sent in the message.
+ sensor_frame: frame_from_message
+
+#The data_type parameter specifies what message type to expect for the topic. The
+#two supported message types at this point are LaserScan and PointCloud.
+ data_type: LaserScan
+
+#The expected_update_rate parameter specifies the delay between messages that the Costmap2DROS
+#object will tolerate. For example, we expect that the base_scan should come in at 20Hz, which is
+#0.05 seconds between messages. However, we are willing to tolerate some jitter and want
+#to be warned when the time between messages exceeds 0.2 seconds.
+ expected_update_rate: 0.2
+
+#The observation_persistence parameter controls how long a message/observation from the topic persists
+#in its associated observation buffer. In this case, we'll set the persistence to 0.0 seconds meaning
+#we'll only keep the latest scan. This is fine for the base_scan because it is a planar laser that updates
+#at 20Hz. However, consider the case where we have an actuated sensor, such as a tilting laser. In that
+#case, we would set the observation_persistence to be equal to the tilting period. So, if the laser takes
+#2 seconds to do a full sweep of the world, we'll want to set the observation_persistence parameter to 2
+#seconds to make sure that we keep scans for that amount of time.
+ observation_persistence: 0.0
+
+#The marking and clearing parameters specify what functions the topic should be used for. If marking is set
+#to true, observations from the topic will be put into the costmap as obstacles. If marking is set to
+#false, observations from the topic won't be put into the costmap as obstacles. If clearing is set to true,
+#observations from the topic will be used to clear out freespace in the costmap. If clearing is set to false,
+#observations from the topic won't be used to clear out freespace. In the case of the base_scan, we want to
+#both put obstacles in and clear obstacles from the costmap so we'll set both clearing and marking to be true.
+ marking: true
+ clearing: true
+
+#The max_obstacle_height parameter specifies the maximum height reading from a sensor to be considered when
+#either clearing or marking. The min_obstacle_height parameter specifies the minimum height reading from a
+#sensor to be considered when clearing or marking. The base_scan corresponds to a planar laser sensor, so it
+#doesn't matter what we set these values to as long as the actual height of the laser falls in-between them.
+ max_obstacle_height: 0.4
+ min_obstacle_height: 0.08
+
+#This parameter controls whether or not the Costmap2DROS object should initialize itself from the static map.
+#If this parameter is set to true, the Costmap2DROS object will make a service call to the map_server and
+#initialize itself based on the map returned. If the static_map parameter is set to false, the Costmap2DROS
+#object will be initialized only with the data that it receives from its sensors. Since we want to demonstrate
+#creating costmaps of arbitrary sizes, we'll set static_map to false here.
static_map: false
+
+#When the rolling_window parameter is set to true, the Costmap2DROS object will always maintain a map that is
+#centered around the current position of the robot. As the robot moves in the world, so too will the costmap.
+#This means that the edges of the costmap will be clipped as the robot moves. If this parameter is not set, the
+#map will stay fixed at its original origin. If the robot moves off the map in this situation, the costmap will
+#not move with it. All queries to regions outside of the costmap will return errors.
rolling_window: true
+
+#The width and height parameters set the width and height of the costmap in meters. To keep a map of 10 meters
+#by 10 meters with the robot at the center, we'll set the values accordingly.
width: 10.0
height: 10.0
-resolution: 0.05
+resolution: 0.025
map_type: voxel
origin_z: 0.0
Modified: pkg/trunk/nav/nav_apps/costmap_2d_tutorials/mainpage.dox
===================================================================
--- pkg/trunk/nav/nav_apps/costmap_2d_tutorials/mainpage.dox 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/nav/nav_apps/costmap_2d_tutorials/mainpage.dox 2009-06-29 21:30:21 UTC (rev 17895)
@@ -2,8 +2,6 @@
\mainpage
\htmlinclude manifest.html
-\b costmap_2d_tutorials is ...
-
<!--
In addition to providing an overview of your package,
this is the section where the specification and design/architecture
@@ -12,9 +10,30 @@
You can then link to this documentation page from the Wiki.
-->
+\b costmap_2d_tutorials provides example code for the costmap_2d package.
+Specifically, it details the construction of a Costmap2DROS object and its use.
-\section codeapi Code API
+\section overview Overview
+There are two main ways to use a costmap_2d::Costmap2DROS object. The first is to create a costmap::Costmap2D
+object and manage updating it yourself. The second, and encouraged method, is
+to use a ROS wrapper (costmap_2d::Costmap2DROS) for the costmap that manages the map for
+you, but allows you to get a copy of the underlying costmap_2d::Costmap2D object at any time.
+See below for an example of costmap_2d::Costmap2DROS construction and configuration.
+\section construction Costmap2DROS Construction
+Constructing a costmap_2d::Costmap2DROS object is a simple as passing in a name and a reference to a tf::TransformListener.
+All the configuration of the costmap_2d::Costmap2DROS is handled by setting parameters on the parameter sever.
+\dontinclude src/costmap_test.cpp
+\skip main
+\until }
+
+\section configuration Costmap2DROS Configuration
+Each costmap_2d::Costmap2DROS object can be configured via the parameter server.
+Below is an example configuration of a simple costmap that subscribes to the "base_laser"
+sensor.
+
+\include launch_example/costmap_params.yaml
+
<!--
Provide links to specific auto-generated API documentation within your
package that is of particular interest to a reader. Doxygen will
@@ -116,4 +135,4 @@
END: Command-Line Tools Section -->
-*/
\ No newline at end of file
+*/
Modified: pkg/trunk/stacks/world_models/costmap_2d/include/costmap_2d/observation_buffer.h
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/include/costmap_2d/observation_buffer.h 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/stacks/world_models/costmap_2d/include/costmap_2d/observation_buffer.h 2009-06-29 21:30:21 UTC (rev 17895)
@@ -58,7 +58,7 @@
/**
* @brief Constructs an observation buffer
* @param topic_name The topic of the observations, used as an identifier for error and warning messages
- * @param observation_keep_time Defines the persistance of observations in seconds, 0 means only keep the latest
+ * @param observation_keep_time Defines the persistence of observations in seconds, 0 means only keep the latest
* @param expected_update_rate How often this buffer is expected to be updated, 0 means there is no limit
* @param min_obstacle_height The minimum height of a hitpoint to be considered legal
* @param max_obstacle_height The minimum height of a hitpoint to be considered legal
Modified: pkg/trunk/stacks/world_models/costmap_2d/launch_costmap_2d_ros.xml
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/launch_costmap_2d_ros.xml 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/stacks/world_models/costmap_2d/launch_costmap_2d_ros.xml 2009-06-29 21:30:21 UTC (rev 17895)
@@ -30,13 +30,13 @@
<param name="costmap/observation_topics" value="tilt_scan" />
<param name="costmap/base_scan/sensor_frame" value="frame_from_message" />
- <param name="costmap/base_scan/observation_persistance" value="0.0" />
+ <param name="costmap/base_scan/observation_persistence" value="0.0" />
<param name="costmap/base_scan/expected_update_rate" value="0.2" />
<param name="costmap/base_scan/data_type" value="LaserScan" />
<param name="costmap/base_scan/clearing" value="true" />
<param name="costmap/tilt_scan/sensor_frame" value="frame_from_message" />
- <param name="costmap/tilt_scan/observation_persistance" value="10.0" />
+ <param name="costmap/tilt_scan/observation_persistence" value="10.0" />
<param name="costmap/tilt_scan/expected_update_rate" value="0.2" />
<param name="costmap/tilt_scan/data_type" value="LaserScan" />
<param name="costmap/tilt_scan/clearing" value="true" />
Modified: pkg/trunk/stacks/world_models/costmap_2d/mainpage.dox
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/mainpage.dox 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/stacks/world_models/costmap_2d/mainpage.dox 2009-06-29 21:30:21 UTC (rev 17895)
@@ -27,7 +27,7 @@
//set parameters before construction of the Costmap2DROS object... we'll use the base laser to add data to this costmap
ros_node_.setParam("~costmap/observation_topics", "base_scan");
- ros_node_.setParam("~costmap/base_scan/observation_persistance", 0.0);
+ ros_node_.setParam("~costmap/base_scan/observation_persistence", 0.0);
ros_node_.setParam("~costmap/base_scan/expected_update_rate", 0.2);
ros_node_.setParam("~costmap/base_scan/data_type", "LaserScan");
ros_node_.setParam("~costmap/base_scan/clearing", "true");
@@ -91,7 +91,7 @@
<ul>
<li><b>~topic_name/sensor_frame</b>, <i>string</i> <br>The frame of the origin of the sensor. Set to "frame_from_message" to attempt to read the frame from sensor data.</li>
<br><br>
- <li><b>~topic_name/observation_persistance</b>, <i>double</i> <br>How long to keep each sensor reading in seconds. A value of 0.0 will only keep the most recent reading.</li>
+ <li><b>~topic_name/observation_persistence</b>, <i>double</i> <br>How long to keep each sensor reading in seconds. A value of 0.0 will only keep the most recent reading.</li>
<br><br>
<li><b>~topic_name/expected_update_rate</b>, <i>double</i> <br>How often to expect a reading from a sensor in secongs. A value of 0.0 will allow infinite time between readings.</li>
<br><br>
Modified: pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-06-29 21:30:21 UTC (rev 17895)
@@ -87,7 +87,7 @@
double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
std::string sensor_frame, data_type;
ros_node_.param("~" + topic + "/sensor_frame", sensor_frame, std::string("frame_from_message"));
- ros_node_.param("~" + topic + "/observation_persistance", observation_keep_time, 0.0);
+ ros_node_.param("~" + topic + "/observation_persistence", observation_keep_time, 0.0);
ros_node_.param("~" + topic + "/expected_update_rate", expected_update_rate, 0.0);
ros_node_.param("~" + topic + "/data_type", data_type, std::string("PointCloud"));
ros_node_.param("~" + topic + "/min_obstacle_height", min_obstacle_height, 0.05);
@@ -111,7 +111,7 @@
if(clearing)
clearing_buffers_.push_back(observation_buffers_.back());
- ROS_DEBUG("Created an observation buffer for topic %s, expected update rate: %.2f, observation persistance: %.2f", topic.c_str(), expected_update_rate, observation_keep_time);
+ ROS_DEBUG("Created an observation buffer for topic %s, expected update rate: %.2f, observation persistence: %.2f", topic.c_str(), expected_update_rate, observation_keep_time);
//create a callback for the topic
if(data_type == "LaserScan"){
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|