|
From: <is...@us...> - 2009-06-25 18:12:35
|
Revision: 17682
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17682&view=rev
Author: isucan
Date: 2009-06-25 18:11:51 +0000 (Thu, 25 Jun 2009)
Log Message:
-----------
some documentation
Modified Paths:
--------------
pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp
pkg/trunk/util/robot_self_filter/include/robot_self_filter/self_mask.h
pkg/trunk/util/robot_self_filter/mainpage.dox
pkg/trunk/util/robot_self_filter/src/self_filter.cpp
pkg/trunk/util/robot_self_filter/src/test_filter.cpp
Modified: pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp 2009-06-25 18:10:04 UTC (rev 17681)
+++ pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp 2009-06-25 18:11:51 UTC (rev 17682)
@@ -109,7 +109,6 @@
// configure the self mask and the message notifier
- sf_.configure();
std::vector<std::string> frames;
sf_.getLinkFrames(frames);
if (std::find(frames.begin(), frames.end(), robotFrame_) == frames.end())
Modified: pkg/trunk/util/robot_self_filter/include/robot_self_filter/self_mask.h
===================================================================
--- pkg/trunk/util/robot_self_filter/include/robot_self_filter/self_mask.h 2009-06-25 18:10:04 UTC (rev 17681)
+++ pkg/trunk/util/robot_self_filter/include/robot_self_filter/self_mask.h 2009-06-25 18:11:51 UTC (rev 17682)
@@ -68,6 +68,7 @@
/** \brief Construct the filter */
SelfMask(tf::TransformListener &tf) : rm_("robot_description"), tf_(tf)
{
+ configure();
}
/** \brief Destructor to clean up
@@ -79,8 +80,6 @@
delete bodies_[i].body;
}
- bool configure(void);
-
/** \brief Compute the mask for a given pointcloud. If a mask element is true, the point
is outside the robot
*/
@@ -93,13 +92,18 @@
setup is performed, assumeFrame() should be called before use */
bool getMask(double x, double y, double z) const;
- /** Get the set of frames that correspond to the links */
+ /** \brief Get the set of frames that correspond to the links */
void getLinkFrames(std::vector<std::string> &frames) const;
private:
+ /** \brief Configure the filter. */
+ bool configure(void);
+
+ /** \brief Compute bounding spheres for the checked robot links. */
void computeBoundingSpheres(void);
+ /** \brief Perform the actual mask computation. */
void maskSimple(const robot_msgs::PointCloud& data_in, std::vector<bool> &mask);
planning_environment::RobotModels rm_;
Modified: pkg/trunk/util/robot_self_filter/mainpage.dox
===================================================================
--- pkg/trunk/util/robot_self_filter/mainpage.dox 2009-06-25 18:10:04 UTC (rev 17681)
+++ pkg/trunk/util/robot_self_filter/mainpage.dox 2009-06-25 18:11:51 UTC (rev 17682)
@@ -2,8 +2,14 @@
\mainpage
\htmlinclude manifest.html
-\b new_robot_self_filter is ...
+\b robot_self_filter can either remove points from a pointcloud that
+are on the robot (parts the robot can see of itself) or it can
+annotate the points by adding a channel with a name of choice that
+will have values of 1.0 (point is outside the robot) or -1.0 (point is
+on the robot)
+
+
<!--
In addition to providing an overview of your package,
this is the section where the specification and design/architecture
@@ -13,7 +19,8 @@
-->
-\section codeapi Code API
+<!-- \section codeapi Code API
+-->
<!--
Provide links to specific auto-generated API documentation within your
@@ -34,86 +41,80 @@
APPEAR IN THE CODE. You should list names of every topic, service and
parameter used in your code. There is a template below that you can
use to document each node separately.
+-->
List of nodes:
-- \b node_name1
-- \b node_name2
--->
+- \b self_filter
+- \b test_filter
<!-- START: copy from here to 'END' for each node
<hr>
-\subsection node_name node_name
+\subsection self_filter self_filter
-node_name does (provide a basic description of your node)
+self_filter listents to a pointcloud on the 'cloud_in' topic and
+broadcasts a pointcloud on 'cloud_out' topic. There are two modes of
+using this node: it can either remove points that are on the robot
+from the input cloud and only broadcast the rest, or it can annotate
+the points with another channel with a name of choice.
+
\subsubsection Usage
\verbatim
-$ node_type1 [standard ROS args]
+$ self_filter [standard ROS params]
\endverbatim
\par Example
\verbatim
-$ node_type1
+$ self_filter robot_description:=robotdesc/pr2 cloud_in:=tilt_cloud cloud_out:=tilt_cloud_filtered
\endverbatim
\subsubsection topics ROS topics
Subscribes to:
-- \b "in": [std_msgs/FooType] description of in
+- \b "cloud_in": [robot_msgs/PointCloud]
Publishes to:
-- \b "out": [std_msgs/FooType] description of out
+- \b "cloud_out": [robot_msgs/PointCloud]
\subsubsection parameters ROS parameters
Reads the following parameters from the parameter server
-- \b "~param_name" : \b [type] description of param_name
-- \b "~my_param" : \b [string] description of my_param
+- \b "~annotate" : \b [string] if specified, this channel name will be added to the input pointcloud
+and no points will be removed. The values of this channel will be only -1.0 (point on robot) and 1.0
+(point outside)
-Sets the following parameters on the parameter server
+- \b "~robot_description" : \b [string] the URDF description of the robot
-- \b "~param_name" : \b [type] description of param_name
-\subsubsection services ROS services
-- \b "foo_service": [std_srvs/FooType] description of foo_service
+\subsection test_filter test_filter
+test_filter randomly generates points around & inside the robot and
+uses the filter to only keep the ones inside or the ones outside. The
+kept set is then sent as a visualization messages to rviz. This
+provides a simpl means to test the filter.
-END: copy for each node -->
-
-
-<!-- START: Uncomment if you have any command-line tools
-
-\section commandline Command-line tools
-
-This section is a catch-all for any additional tools that your package
-provides or uses that may be of use to the reader. For example:
-
-- tools/scripts (e.g. rospack, roscd)
-- roslaunch .launch files
-- xmlparam files
-
-\subsection script_name script_name
-
-Description of what this script/file does.
-
\subsubsection Usage
\verbatim
-$ ./script_name [args]
+$ test_filter [standard ROS params]
\endverbatim
\par Example
\verbatim
-$ ./script_name foo bar
+$ test_filter robot_description:=robotdesc/pr2
\endverbatim
-END: Command-Line Tools Section -->
+\subsubsection parameters ROS parameters
-*/
\ No newline at end of file
+Reads the following parameters from the parameter server
+
+- \b "~robot_description" : \b [string] the URDF description of the robot
+
+*/
Modified: pkg/trunk/util/robot_self_filter/src/self_filter.cpp
===================================================================
--- pkg/trunk/util/robot_self_filter/src/self_filter.cpp 2009-06-25 18:10:04 UTC (rev 17681)
+++ pkg/trunk/util/robot_self_filter/src/self_filter.cpp 2009-06-25 18:11:51 UTC (rev 17682)
@@ -44,7 +44,6 @@
SelfFilter(void) : sf_(tf_), mn_(tf_, boost::bind(&SelfFilter::cloudCallback, this, _1), "cloud_in", "", 1)
{
- sf_.configure();
std::vector<std::string> frames;
sf_.getLinkFrames(frames);
mn_.setTargetFrame(frames);
Modified: pkg/trunk/util/robot_self_filter/src/test_filter.cpp
===================================================================
--- pkg/trunk/util/robot_self_filter/src/test_filter.cpp 2009-06-25 18:10:04 UTC (rev 17681)
+++ pkg/trunk/util/robot_self_filter/src/test_filter.cpp 2009-06-25 18:11:51 UTC (rev 17682)
@@ -45,7 +45,6 @@
TestSelfFilter(void) : sf_(tf_)
{
id_ = 1;
- sf_.configure();
vmPub_ = nodeHandle_.advertise<visualization_msgs::Marker>("visualization_marker", 10240);
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|