|
From: <tf...@us...> - 2009-08-24 23:57:17
|
Revision: 22791
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=22791&view=rev
Author: tfoote
Date: 2009-08-24 23:57:09 +0000 (Mon, 24 Aug 2009)
Log Message:
-----------
merging back filters change, door_demos_gazebo passes and 2dnav_gazebo runs
r31481@agn (orig r21824): tfoote | 2009-08-13 14:02:29 -0700
creating branch to make filters dynamically load
r31696@agn (orig r21981): tfoote | 2009-08-16 18:37:27 -0700
compiling example plugin
r31697@agn (orig r21982): tfoote | 2009-08-16 19:47:40 -0700
passing test
r31698@agn (orig r21983): tfoote | 2009-08-16 19:48:15 -0700
adding export
r31860@agn (orig r22114): tfoote | 2009-08-17 23:19:14 -0700
functioning dynamically loaded filters from offline work
r31862@agn (orig r22116): tfoote | 2009-08-17 23:22:14 -0700
adding multi library support to plugin xml parser with plugin_libraries top level tag
r31895@agn (orig r22147): tfoote | 2009-08-18 10:32:24 -0700
removing unused package
r31904@agn (orig r22153): tfoote | 2009-08-18 11:20:48 -0700
cleaning up debugging messages
r31919@agn (orig r22161): tfoote | 2009-08-18 13:50:36 -0700
new MultiChannelFilterBase
r31920@agn (orig r22162): tfoote | 2009-08-18 14:00:11 -0700
transfer function test recovered
r32021@agn (orig r22256): tfoote | 2009-08-18 22:22:21 -0700
tests passing
r32028@agn (orig r22263): tfoote | 2009-08-18 23:14:34 -0700
compiling under new architecture
r32067@agn (orig r22296): tfoote | 2009-08-19 11:09:09 -0700
catching XML parse failure
r32071@agn (orig r22300): tfoote | 2009-08-19 11:18:15 -0700
scan_to_cloud running
r32107@agn (orig r22330): tfoote | 2009-08-19 14:27:17 -0700
adding two filter test to make sure we can load from different manifests
r32119@agn (orig r22340): tfoote | 2009-08-19 15:34:06 -0700
lots of debugging output
r32155@agn (orig r22375): tfoote | 2009-08-19 18:03:04 -0700
fixing types
r32165@agn (orig r22383): tfoote | 2009-08-19 18:21:24 -0700
removing redundant boost flag now and making multi channel actually configure with multichannel
r32178@agn (orig r22393): tfoote | 2009-08-19 19:33:42 -0700
explicit MultiChannel vs single for FilterChain
r32186@agn (orig r22401): tfoote | 2009-08-19 20:06:20 -0700
single channel filter working too
r32189@agn (orig r22402): tfoote | 2009-08-19 20:16:57 -0700
more tests of single channel mean filter
r32192@agn (orig r22404): tfoote | 2009-08-19 20:34:46 -0700
float precision for median filter added
r32193@agn (orig r22405): tfoote | 2009-08-19 20:35:19 -0700
forgot xml
r32199@agn (orig r22410): tfoote | 2009-08-19 21:13:40 -0700
shadows.launch running
r32232@agn (orig r22429): tfoote | 2009-08-20 09:53:38 -0700
exporting median filters with float type
r32233@agn (orig r22430): tfoote | 2009-08-20 09:57:11 -0700
all launch files running successfully in laser_scan package
r32235@agn (orig r22432): tfoote | 2009-08-20 10:18:55 -0700
fixing for filters API change
r32237@agn (orig r22434): tfoote | 2009-08-20 10:33:55 -0700
fixing for filters API change
r32242@agn (orig r22438): tfoote | 2009-08-20 10:48:53 -0700
fixing for filters API change
r32246@agn (orig r22441): tfoote | 2009-08-20 11:05:01 -0700
doesn't actually need filters
r32249@agn (orig r22443): tfoote | 2009-08-20 11:22:38 -0700
blacklisting intead of porting for it's out of scope for M3
r32250@agn (orig r22444): tfoote | 2009-08-20 11:28:56 -0700
fixing for new filters API
r32253@agn (orig r22447): tfoote | 2009-08-20 12:00:55 -0700
switching to new filters API
r32270@agn (orig r22461): tfoote | 2009-08-20 13:31:51 -0700
blacklisting packages the haven't bee converted #2516
r32271@agn (orig r22462): tfoote | 2009-08-20 13:38:41 -0700
fixing blacklist location
r32273@agn (orig r22463): tfoote | 2009-08-20 13:41:55 -0700
makeing makefile more robust
r32302@agn (orig r22487): eitanme | 2009-08-20 16:28:21 -0700
Adding parsing from the parameter server to filter base
r32307@agn (orig r22492): tfoote | 2009-08-20 16:52:21 -0700
switching to simpler constructor
r32323@agn (orig r22508): eitanme | 2009-08-20 18:11:45 -0700
Working towards re-writing things. FilterBase now parses XmlRpc values as discussed
r32329@agn (orig r22514): tfoote | 2009-08-20 18:23:44 -0700
one more filter to migrate
r32339@agn (orig r22521): eitanme | 2009-08-20 18:45:13 -0700
Compiling version of the new filter chain configure implementation
r32346@agn (orig r22528): eitanme | 2009-08-20 19:39:40 -0700
Not sure if this compiles or not, but this should be a complete impelementation at least
r32347@agn (orig r22529): eitanme | 2009-08-20 19:46:40 -0700
Compiling version of new filter chain and base
r32348@agn (orig r22530): tfoote | 2009-08-20 19:48:39 -0700
switching first to rostest
r32351@agn (orig r22533): tfoote | 2009-08-20 20:01:15 -0700
fixing filters to use new param syntax, not compiling
r32372@agn (orig r22553): tfoote | 2009-08-21 10:21:41 -0700
only xmlrpc errors now
r32394@agn (orig r22574): tfoote | 2009-08-21 12:47:24 -0700
Now passing single filter tests, still need to work a bit on the chains
r32395@agn (orig r22575): tfoote | 2009-08-21 13:01:19 -0700
chain tests passing
r32403@agn (orig r22582): tfoote | 2009-08-21 13:19:42 -0700
transfer function tests passing
r32404@agn (orig r22583): tfoote | 2009-08-21 13:21:17 -0700
better debugging output
r32414@agn (orig r22592): eitanme | 2009-08-21 13:52:13 -0700
Adding a call to getParam for an XmlRpc value
r32416@agn (orig r22593): tfoote | 2009-08-21 14:15:11 -0700
making chain configure from rpc public
r32418@agn (orig r22595): tfoote | 2009-08-21 14:19:18 -0700
compiling with filters from params
r32433@agn (orig r22604): tfoote | 2009-08-21 15:27:37 -0700
fixing unittest which erroneously passed before
r32437@agn (orig r22607): eitanme | 2009-08-21 15:49:14 -0700
Allowing for empty filter chains
r32440@agn (orig r22609): eitanme | 2009-08-21 15:51:46 -0700
Checking in FILTER_LIST
r32441@agn (orig r22610): eitanme | 2009-08-21 15:52:43 -0700
new task
r32442@agn (orig r22611): tfoote | 2009-08-21 15:55:52 -0700
switched default_scan_shadows to use yaml
r32444@agn (orig r22613): eitanme | 2009-08-21 16:00:34 -0700
Removing filter list now that its a spreadsheet
r32448@agn (orig r22616): tfoote | 2009-08-21 16:11:30 -0700
xml -> yaml but can't rename grrrr
r32453@agn (orig r22621): tfoote | 2009-08-21 16:35:07 -0700
filter_chain into yaml
r32454@agn (orig r22622): eitanme | 2009-08-21 16:35:16 -0700
Moving code and tests to filter_chain naming convention
r32460@agn (orig r22628): eitanme | 2009-08-21 16:54:39 -0700
Moving launch files to work with the new filters
r32466@agn (orig r22633): tfoote | 2009-08-21 17:29:38 -0700
fixed all xml -> yaml and launch files
r32467@agn (orig r22634): eitanme | 2009-08-21 17:34:07 -0700
moving to work with new filters
r32470@agn (orig r22637): eitanme | 2009-08-21 19:56:46 -0700
Checking in a half compiling effort at turning xml into an xml rpc value... sorry Tully... I'll work on this more later
r32479@agn (orig r22643): tfoote | 2009-08-22 17:26:44 -0700
fixing compile and changing from xml to yaml
r32483@agn (orig r22647): tfoote | 2009-08-22 17:57:11 -0700
fixing namespace
r32484@agn (orig r22648): tfoote | 2009-08-22 17:58:55 -0700
switching from xml to yaml filters
r32487@agn (orig r22651): tfoote | 2009-08-22 19:32:57 -0700
new filters format tests passing if migrated
r32495@agn (orig r22655): tfoote | 2009-08-22 22:24:17 -0700
compiling. . . passing all zero tests
r32496@agn (orig r22656): tfoote | 2009-08-22 22:46:39 -0700
switching to reading from param server directly instead of xml off the parameter server
r32497@agn (orig r22657): tfoote | 2009-08-22 22:57:57 -0700
fixing controller file for use with xmlrpc
r32498@agn (orig r22658): tfoote | 2009-08-23 00:20:41 -0700
switching xml to yaml filter calls
r32499@agn (orig r22659): tfoote | 2009-08-23 00:28:18 -0700
converting to new filters and yaml
r32501@agn (orig r22661): tfoote | 2009-08-23 00:45:10 -0700
fixing typo
r32502@agn (orig r22662): tfoote | 2009-08-23 00:48:15 -0700
xml->yaml filters
r32503@agn (orig r22663): tfoote | 2009-08-23 00:59:23 -0700
xml->yaml filters
r32504@agn (orig r22664): tfoote | 2009-08-23 00:59:39 -0700
xml->yaml filters
r32508@agn (orig r22668): tfoote | 2009-08-23 01:24:47 -0700
changing xml syntax for xmlrpc format
r32591@agn (orig r22736): tfoote | 2009-08-24 12:24:01 -0700
robusitfying makefiles
r32594@agn (orig r22739): tfoote | 2009-08-24 12:49:25 -0700
makeing Makefiles more robust
r32634@agn (orig r22777): eitanme | 2009-08-24 15:48:02 -0700
Fixing XML filter specification... not all that pretty though, should be changed eventually to read from the param server
r32636@agn (orig r22778): tfoote | 2009-08-24 16:01:35 -0700
changing to debug
r32646@agn (orig r22788): tfoote | 2009-08-24 16:50:56 -0700
fixing script and usage
Modified Paths:
--------------
pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/config/lasers_and_filters.xml
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml
pkg/trunk/demos/door_demos_gazebo/launch/perception_planner.xml
pkg/trunk/demos/milestone2/milestone2_actions/config/perception.xml
pkg/trunk/demos/plug_in/make_lowpass.m
pkg/trunk/highlevel/plugs/plugs_core/scripts/make_lowpass.m
pkg/trunk/mapping/door_tracker/launch/door_tracker.launch
pkg/trunk/mapping/door_tracker/src/door_tracker.cpp
pkg/trunk/mapping/hallway_tracker/launch/hallway_tracker.launch
pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp
pkg/trunk/pr2/life_test/laser_tilt_test/life_test/controllers.xml
pkg/trunk/robot_descriptions/pr2/pr2_experimental_controllers/laser_tilt/laser_tilt_controller.xml
pkg/trunk/sandbox/3dnav_pr2/launch/perception/laser+stereo-perception.launch
pkg/trunk/sandbox/3dnav_pr2/launch/perception/laser-perception.launch
pkg/trunk/sandbox/annotated_map_builder/config/perception.xml
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/cartesian_hybrid_controller.h
pkg/trunk/sandbox/experimental_controllers/src/cartesian_hybrid_controller.cpp
pkg/trunk/stacks/common/filters/CMakeLists.txt
pkg/trunk/stacks/common/filters/include/filters/filter_base.h
pkg/trunk/stacks/common/filters/include/filters/filter_chain.h
pkg/trunk/stacks/common/filters/include/filters/mean.h
pkg/trunk/stacks/common/filters/include/filters/median.h
pkg/trunk/stacks/common/filters/include/filters/transfer_function.h
pkg/trunk/stacks/common/filters/manifest.xml
pkg/trunk/stacks/common/filters/src/transfer_function.cpp
pkg/trunk/stacks/common/filters/test/test_chain.cpp
pkg/trunk/stacks/common/filters/test/test_mean.cpp
pkg/trunk/stacks/common/filters/test/test_median.cpp
pkg/trunk/stacks/common/filters/test/test_transfer_function.cpp
pkg/trunk/stacks/common/laser_scan/CMakeLists.txt
pkg/trunk/stacks/common/laser_scan/footprint.launch
pkg/trunk/stacks/common/laser_scan/include/laser_scan/footprint_filter.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/intensity_filter.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/laser_scan.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/median_filter.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/point_cloud_footprint_filter.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/scan_shadows_filter.h
pkg/trunk/stacks/common/laser_scan/intensity_demo.launch
pkg/trunk/stacks/common/laser_scan/manifest.xml
pkg/trunk/stacks/common/laser_scan/median_filter.launch
pkg/trunk/stacks/common/laser_scan/multi.launch
pkg/trunk/stacks/common/laser_scan/shadows.launch
pkg/trunk/stacks/common/laser_scan/src/generic_laser_filter_node.cpp
pkg/trunk/stacks/common/laser_scan/src/laser_scan.cc
pkg/trunk/stacks/common/laser_scan/src/scan_to_cloud.cpp
pkg/trunk/stacks/common/laser_scan/test/projection_test.cpp
pkg/trunk/stacks/geometry/bullet/Makefile.bullet
pkg/trunk/stacks/geometry/kdl/Makefile.orig
pkg/trunk/stacks/laser_drivers/point_cloud_assembler/manifest.xml
pkg/trunk/stacks/laser_drivers/point_cloud_assembler/src/laser_scan_assembler_srv.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/launch/perception.xml
pkg/trunk/stacks/semantic_mapping/door_handle_detector/launch/setup_for_recording.launch
pkg/trunk/stacks/trex/trex_pr2_writing_test/launch/head_cart/perception.launch
pkg/trunk/stacks/trex/trex_pr2_writing_test/launch/perception.launch
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/launch/outlet_coarse_detection/perception.launch
Added Paths:
-----------
pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/ROS_BUILD_BLACKLIST
pkg/trunk/motion_planning/planning_research/pm_wrapper/include/sbpl_pm_wrapper/
pkg/trunk/motion_planning/planning_research/pm_wrapper/include/sbpl_pm_wrapper/pm_wrapper.h
pkg/trunk/sandbox/3dnav_pr2/ROS_BUILD_BLACKLIST
pkg/trunk/sandbox/joint_waypoint_controller/ROS_BUILD_BLACKLIST
pkg/trunk/sandbox/spline_smoother/ROS_BUILD_BLACKLIST
pkg/trunk/sandbox/trajectory_controllers/ROS_BUILD_BLACKLIST
pkg/trunk/stacks/common/filters/default_plugins.xml
pkg/trunk/stacks/common/filters/src/mean.cpp
pkg/trunk/stacks/common/filters/src/median.cpp
pkg/trunk/stacks/common/filters/test/test_chain.launch
pkg/trunk/stacks/common/filters/test/test_chain.yaml
pkg/trunk/stacks/common/filters/test/test_mean.launch
pkg/trunk/stacks/common/filters/test/test_mean.yaml
pkg/trunk/stacks/common/filters/test/test_median.launch
pkg/trunk/stacks/common/filters/test/test_median.yaml
pkg/trunk/stacks/common/filters/test/test_transfer_function.launch
pkg/trunk/stacks/common/filters/test/test_transfer_function.yaml
pkg/trunk/stacks/common/laser_scan/default_scan_shadows.yaml
pkg/trunk/stacks/common/laser_scan/footprint.filters.yaml
pkg/trunk/stacks/common/laser_scan/intensity_demo.filters.yaml
pkg/trunk/stacks/common/laser_scan/laser_scan_plugins.xml
pkg/trunk/stacks/common/laser_scan/median_filter_5.yaml
pkg/trunk/stacks/common/laser_scan/multi.yaml
pkg/trunk/stacks/common/laser_scan/point_cloud_footprint.filters.yaml
pkg/trunk/stacks/common/laser_scan/src/laser_scan_filters.cpp
pkg/trunk/stacks/common/laser_scan/src/median_filter.cpp
pkg/trunk/stacks/common/laser_scan/src/pointcloud_filters.cpp
pkg/trunk/util/iir_filters/ROS_BUILD_BLACKLIST
Removed Paths:
-------------
pkg/trunk/stacks/common/filters/test/test_factory.cpp
pkg/trunk/stacks/common/laser_scan/default_scan_shadows.xml
pkg/trunk/stacks/common/laser_scan/footprint.filters.xml
pkg/trunk/stacks/common/laser_scan/intensity_demo.filters.xml
pkg/trunk/stacks/common/laser_scan/median_filter_5.xml
pkg/trunk/stacks/common/laser_scan/multi.xml
pkg/trunk/stacks/common/laser_scan/point_cloud_footprint.filters.xml
Property Changed:
----------------
pkg/trunk/
Property changes on: pkg/trunk
___________________________________________________________________
Modified: svk:merge
- 637b03a7-42c1-4bbd-8d43-e365e379942c:/prfilters:13971
637b03a7-42c1-4bbd-8d43-e365e379942c:/rosTF_to_tf:9746
920d6130-5740-4ec1-bb1a-45963d5fd813:/costmap_rework_branch:20583
920d6130-5740-4ec1-bb1a-45963d5fd813:/frameidpr:7015
920d6130-5740-4ec1-bb1a-45963d5fd813:/nav_rework:21482
920d6130-5740-4ec1-bb1a-45963d5fd813:/users/josh-pr:11755
920d6130-5740-4ec1-bb1a-45963d5fd813:/wgpkgtrunk:5865
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/action_branch:20116
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/common_msgs-0.1-v2:20514
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/common_msgs-0.1-v3:20628
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/common_msgs_0.1:20375
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/josh:10136
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/milestone2:16602
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/nav_rework:17337
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/plugin_branch:20980
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/pluginlib_rework:22236
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/rosbus:261
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/tags/milestone2_tags/milestone2_final:16577
+ 637b03a7-42c1-4bbd-8d43-e365e379942c:/prfilters:13971
637b03a7-42c1-4bbd-8d43-e365e379942c:/rosTF_to_tf:9746
920d6130-5740-4ec1-bb1a-45963d5fd813:/costmap_rework_branch:20583
920d6130-5740-4ec1-bb1a-45963d5fd813:/frameidpr:7015
920d6130-5740-4ec1-bb1a-45963d5fd813:/nav_rework:21482
920d6130-5740-4ec1-bb1a-45963d5fd813:/users/josh-pr:11755
920d6130-5740-4ec1-bb1a-45963d5fd813:/wgpkgtrunk:5865
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/action_branch:20116
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/common_msgs-0.1-v2:20514
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/common_msgs-0.1-v3:20628
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/common_msgs_0.1:20375
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/filters_dynamic_loading:22788
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/josh:10136
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/milestone2:16602
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/nav_rework:17337
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/plugin_branch:20980
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/pluginlib_rework:22236
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/rosbus:261
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/tags/milestone2_tags/milestone2_final:16577
Modified: pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/config/lasers_and_filters.xml
===================================================================
--- pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/config/lasers_and_filters.xml 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/config/lasers_and_filters.xml 2009-08-24 23:57:09 UTC (rev 22791)
@@ -9,8 +9,8 @@
<!-- Filter for tilt laser shadowing/veiling -->
<node pkg="laser_scan" type="scan_to_cloud" respawn="true" machine="three" name="tilt_shadow_filter">
- <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
- <param name="cloud_filters" textfile="$(find laser_scan)/point_cloud_footprint.filters.xml" />
+ <rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
+ <rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="tilt_scan" />
<param name="cloud_topic" value="tilt_scan_filtered" />
<param name="high_fidelity" value="true" />
@@ -18,8 +18,8 @@
<!-- Filter for base laser shadowing/veiling -->
<node pkg="laser_scan" type="scan_to_cloud" respawn="true" machine="three" name="base_shadow_filter" >
- <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
- <param name="cloud_filters" textfile="$(find laser_scan)/point_cloud_footprint.filters.xml" />
+ <rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
+ <rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="base_scan" />
<param name="cloud_topic" value="base_scan_marking" />
</node>
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp 2009-08-24 23:57:09 UTC (rev 22791)
@@ -115,8 +115,25 @@
return false ;
}
- d_error_filter.FilterBase<double>::configure((unsigned int)1, filter_elem) ;
+ std::string xml_string;
+ TiXmlElement *struct_elem = filter_elem->FirstChildElement("value");
+ if(!struct_elem)
+ {
+ ROS_ERROR("Xml is missing a <value> tag inside filter spec, cannot parse!");
+ return false;
+ }
+ TiXmlPrinter printer;
+ printer.SetIndent(" ");
+ struct_elem->Accept(&printer);
+ std::string filter_str = printer.Str();
+ ROS_DEBUG("Constructing filter with XML: %s", filter_str.c_str());
+ //xmlrpc_elem->Print(xml_string, 10);
+ int offset = 0;
+ XmlRpc::XmlRpcValue rpc_config(filter_str, &offset);
+ ROS_DEBUG("XmlRpc parsed xml: %s type: %d", rpc_config.toXml().c_str(), rpc_config.getType());
+ d_error_filter.MultiChannelFilterBase<double>::configure((unsigned int)1, rpc_config) ;
+
// ***** Max Rate and Acceleration Elements *****
TiXmlElement *max_rate_elem = config->FirstChildElement("max_rate") ;
if (!max_rate_elem)
@@ -222,11 +239,17 @@
joint_state_->joint_->joint_limit_min_,
joint_state_->joint_->joint_limit_max_,
error) ;
+
+
double dt = time - last_time_ ;
double d_error = (error-last_error_)/dt ;
- double filtered_d_error ;
+ std::vector<double> vin;
+ vin.push_back(d_error);
+ std::vector<double> vout = vin;
+
+ d_error_filter.update(vin, vout) ;
- d_error_filter.update(d_error, filtered_d_error) ;
+ double filtered_d_error = vout[0];
// Add filtering step
// Update pid with d_error added
Modified: pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml 2009-08-24 23:57:09 UTC (rev 22791)
@@ -18,7 +18,6 @@
<depend package="tf_conversions" />
<depend package="kdl" />
<depend package="angles" />
- <depend package="filters" />
<depend package="diagnostic_msgs" />
<depend package="pluginlib" />
<url>http://pr.willowgarage.com</url>
Modified: pkg/trunk/demos/door_demos_gazebo/launch/perception_planner.xml
===================================================================
--- pkg/trunk/demos/door_demos_gazebo/launch/perception_planner.xml 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/demos/door_demos_gazebo/launch/perception_planner.xml 2009-08-24 23:57:09 UTC (rev 22791)
@@ -19,8 +19,8 @@
<!-- Filter for tilt laser shadowing/veiling -->
<node pkg="laser_scan" type="scan_to_cloud" respawn="true" machine="three" name="tilt_shadow_filter">
- <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
- <param name="cloud_filters" textfile="$(find laser_scan)/point_cloud_footprint.filters.xml" />
+ <rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
+ <rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="tilt_scan" />
<param name="cloud_topic" value="tilt_scan_filtered" />
<param name="high_fidelity" value="true" />
@@ -28,8 +28,8 @@
<!-- Filter for base laser shadowing/veiling -->
<node pkg="laser_scan" type="scan_to_cloud" respawn="true" machine="three" name="base_shadow_filter" >
- <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
- <param name="cloud_filters" textfile="$(find laser_scan)/point_cloud_footprint.filters.xml" />
+ <rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
+ <rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="base_scan" />
<param name="cloud_topic" value="base_scan_marking" />
</node>
@@ -37,7 +37,7 @@
<!-- Laser scan assembler for tilt laser -->
<node pkg="point_cloud_assembler" type="laser_scan_assembler_srv" output="screen" name="laser_scan_assembler" respawn="true">
<remap from="scan_in" to="tilt_scan"/>
- <param name="filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
+ <rosparam command="load" ns="filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
<param name="tf_cache_time_secs" type="double" value="10.0" />
<param name="max_scans" type="int" value="1000" />
<param name="ignore_laser_skew" type="bool" value="true" />
Modified: pkg/trunk/demos/milestone2/milestone2_actions/config/perception.xml
===================================================================
--- pkg/trunk/demos/milestone2/milestone2_actions/config/perception.xml 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/demos/milestone2/milestone2_actions/config/perception.xml 2009-08-24 23:57:09 UTC (rev 22791)
@@ -23,8 +23,8 @@
<!-- Filter for tilt laser shadowing/veiling -->
<node pkg="laser_scan" type="scan_to_cloud" respawn="true" machine="three" name="tilt_shadow_filter">
- <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
- <param name="cloud_filters" textfile="$(find laser_scan)/point_cloud_footprint.filters.xml" />
+ <rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
+ <rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="tilt_scan" />
<param name="cloud_topic" value="tilt_scan_filtered" />
<param name="high_fidelity" value="true" />
@@ -32,8 +32,8 @@
<!-- Filter for base laser shadowing/veiling -->
<node pkg="laser_scan" type="scan_to_cloud" respawn="true" machine="three" name="base_shadow_filter" >
- <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
- <param name="cloud_filters" textfile="$(find laser_scan)/point_cloud_footprint.filters.xml" />
+ <rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
+ <rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="base_scan" />
<param name="cloud_topic" value="base_scan_marking" />
</node>
@@ -41,7 +41,7 @@
<!-- Laser scan assembler for tilt laser -->
<node pkg="point_cloud_assembler" type="laser_scan_assembler_srv" name="laser_scan_assembler" respawn="true">
<remap from="scan_in" to="tilt_scan"/>
- <param name="filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
+ <rosparam command="load" ns="filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
<param name="tf_cache_time_secs" type="double" value="10.0" />
<param name="max_scans" type="int" value="1000" />
<param name="ignore_laser_skew" type="bool" value="true" />
Modified: pkg/trunk/demos/plug_in/make_lowpass.m
===================================================================
--- pkg/trunk/demos/plug_in/make_lowpass.m 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/demos/plug_in/make_lowpass.m 2009-08-24 23:57:09 UTC (rev 22791)
@@ -9,6 +9,54 @@
a = [1 (-(1 - alpha))];
b = [alpha 0];
-printf('<filter name="%s" type="TransferFunctionFilter">\n', filter_name);
-printf(' <params a="%f %f" b="%f %f" />\n', a(1), a(2), b(1), b(2));
-printf('</filter>\n');
+#printf('<filter name="%s" type="TransferFunctionFilter">\n', filter_name);
+#printf(' <params a="%f %f" b="%f %f" />\n', a(1), a(2), b(1), b(2));
+#printf('</filter>\n');
+
+printf('<filter>');
+printf('<value>');
+printf('<array>');
+printf('<data>');
+printf('<struct>');
+printf('<member>');
+printf('<name>%s</name>', filter_name);
+printf('<value>d_error_filter</value>');
+printf('</member>');
+printf('<member>');
+printf('<name>type</name>');
+printf('<value>TransferFunctionFilter</value>');
+printf('</member>');
+printf('<member>');
+printf('<name>params</name>');
+printf('<value>');
+printf('<struct>');
+printf('<member>');
+printf('<name>a</name>');
+printf('<value>');
+printf('<array>');
+printf('<data>');
+printf('<value><double>%f</double></value>', a(1));
+printf('<value><double>%f</double></value>', a(2));
+printf('</data>');
+printf('</array>');
+printf('</value>');
+printf('</member>');
+printf('<member>');
+printf('<name>b</name>');
+printf('<value>');
+printf('<array>');
+printf('<data>');
+printf('<value><double>%f</double></value>', b(1));
+printf('<value><double>%f</double></value>', b(2));
+printf('</data>');
+printf('</array>');
+printf('</value>');
+printf('</member>');
+printf('</struct>');
+printf('</value>');
+printf('</member>');
+printf('</struct>');
+printf('</data>');
+printf('</array>');
+printf('</value>');
+printf('</filter>');
Added: pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/ROS_BUILD_BLACKLIST
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/ROS_BUILD_BLACKLIST (rev 0)
+++ pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/ROS_BUILD_BLACKLIST 2009-08-24 23:57:09 UTC (rev 22791)
@@ -0,0 +1 @@
+broken see ticket https://prdev.willowgarage.com/trac/personalrobots/ticket/2516
Modified: pkg/trunk/highlevel/plugs/plugs_core/scripts/make_lowpass.m
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/scripts/make_lowpass.m 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/highlevel/plugs/plugs_core/scripts/make_lowpass.m 2009-08-24 23:57:09 UTC (rev 22791)
@@ -9,6 +9,54 @@
a = [1 (-(1 - alpha))];
b = [alpha 0];
-printf('<filter name="%s" type="TransferFunctionFilter">\n', filter_name);
-printf(' <params a="%f %f" b="%f %f" />\n', a(1), a(2), b(1), b(2));
-printf('</filter>\n');
+#printf('<filter name="%s" type="TransferFunctionFilter">\n', filter_name);
+#printf(' <params a="%f %f" b="%f %f" />\n', a(1), a(2), b(1), b(2));
+#printf('</filter>\n');
+
+printf('<filter>');
+printf('<value>');
+printf('<array>');
+printf('<data>');
+printf('<struct>');
+printf('<member>');
+printf('<name>%s</name>', filter_name);
+printf('<value>d_error_filter</value>');
+printf('</member>');
+printf('<member>');
+printf('<name>type</name>');
+printf('<value>TransferFunctionFilter</value>');
+printf('</member>');
+printf('<member>');
+printf('<name>params</name>');
+printf('<value>');
+printf('<struct>');
+printf('<member>');
+printf('<name>a</name>');
+printf('<value>');
+printf('<array>');
+printf('<data>');
+printf('<value><double>%f</double></value>', a(1));
+printf('<value><double>%f</double></value>', a(2));
+printf('</data>');
+printf('</array>');
+printf('</value>');
+printf('</member>');
+printf('<member>');
+printf('<name>b</name>');
+printf('<value>');
+printf('<array>');
+printf('<data>');
+printf('<value><double>%f</double></value>', b(1));
+printf('<value><double>%f</double></value>', b(2));
+printf('</data>');
+printf('</array>');
+printf('</value>');
+printf('</member>');
+printf('</struct>');
+printf('</value>');
+printf('</member>');
+printf('</struct>');
+printf('</data>');
+printf('</array>');
+printf('</value>');
+printf('</filter>');
Modified: pkg/trunk/mapping/door_tracker/launch/door_tracker.launch
===================================================================
--- pkg/trunk/mapping/door_tracker/launch/door_tracker.launch 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/mapping/door_tracker/launch/door_tracker.launch 2009-08-24 23:57:09 UTC (rev 22791)
@@ -1,6 +1,6 @@
<launch>
<node pkg="door_tracker" type="door_tracker_node" output="screen" name="door_tracker_node">
- <param name="filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
+ <rosparam command="load" ns="filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
</node>
<node pkg="door_tracker" type="door_database_node" output="screen" name="door_database_node"/>
Modified: pkg/trunk/mapping/door_tracker/src/door_tracker.cpp
===================================================================
--- pkg/trunk/mapping/door_tracker/src/door_tracker.cpp 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/mapping/door_tracker/src/door_tracker.cpp 2009-08-24 23:57:09 UTC (rev 22791)
@@ -139,7 +139,7 @@
bool first_time_;
- DoorTracker():message_notifier_(NULL)
+ DoorTracker():message_notifier_(NULL), filter_chain_("sensor_msgs::LaserScan")
{
num_clouds_received_ = 0;
continuous_detection_ = false;
@@ -147,13 +147,7 @@
node_handle_.subscribe("~activate",1,&DoorTracker::activate,this);
ROS_DEBUG("Started door tracker");
//Laser Scan Filtering
- std::string filter_xml;
- node_handle_.param("~filters", filter_xml,std::string("<filters><!--NO Filters defined--></filters>"));
- //ROS_INFO("Got ~filters as: %s\n", filter_xml.c_str());
- TiXmlDocument xml_doc;
- xml_doc.Parse(filter_xml.c_str());
- TiXmlElement * config = xml_doc.RootElement();
- filter_chain_.configure(1, config);
+ filter_chain_.configure("~filters");
done_detection_ = true;
euclidean_cluster_angle_tolerance_ = angles::from_degrees (25.0);
euclidean_cluster_min_pts_ = 20; // 1000 points
@@ -587,7 +581,7 @@
ROS_DEBUG("Found zero clusters");
continue;
}
- ROS_DEBUG("Found %d clusters",clusters.size());
+ ROS_DEBUG("Found %d clusters",(int)clusters.size());
for(int i=0; i < (int) clusters.size(); i++)
{
if((int) clusters[i].size() > sac_min_points_per_model_)
Modified: pkg/trunk/mapping/hallway_tracker/launch/hallway_tracker.launch
===================================================================
--- pkg/trunk/mapping/hallway_tracker/launch/hallway_tracker.launch 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/mapping/hallway_tracker/launch/hallway_tracker.launch 2009-08-24 23:57:09 UTC (rev 22791)
@@ -7,6 +7,6 @@
<param name="p_sac_distance_threshold" type="double" value="0.03" />
<param name="p_min_hallway_width_m" type="double" value="1.0" />
<param name="p_max_hallway_width_m" type="double" value="4.0" />
- <param name="filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
+ <rosparam command="load" ns="filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
</node>
</launch>
Modified: pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp
===================================================================
--- pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp 2009-08-24 23:57:09 UTC (rev 22791)
@@ -104,8 +104,8 @@
laser_scan::LaserProjection projector_; // Used to project laser scans into point clouds
tf::TransformListener *tf_;
- tf::MessageNotifier<sensor_msgs::LaserScan>* message_notifier_;
filters::FilterChain<sensor_msgs::LaserScan> filter_chain_;
+ tf::MessageNotifier<sensor_msgs::LaserScan>* message_notifier_;
/********** Parameters from the param server *******/
std::string base_laser_topic_; // Topic for the laser scan message.
@@ -118,7 +118,7 @@
- HallwayTracker():message_notifier_(NULL)
+ HallwayTracker():filter_chain_("sensor_msgs::LaserScan"), message_notifier_(NULL)
{
node_ = ros::Node::instance();
tf_ = new tf::TransformListener(*node_);
@@ -136,14 +136,8 @@
//eps_angle_ = cloud_geometry::deg2rad (eps_angle_); // convert to radians
//Laser Scan Filtering
- std::string filter_xml;
- node_->param("~filters", filter_xml,std::string("<filters><!--NO Filters defined--></filters>"));
- //ROS_INFO("Got ~filters as: %s\n", filter_xml.c_str());
- TiXmlDocument xml_doc;
- xml_doc.Parse(filter_xml.c_str());
- TiXmlElement * config = xml_doc.RootElement();
- filter_chain_.configure(1, config);
+ filter_chain_.configure("~filters");
// Visualization:
Added: pkg/trunk/motion_planning/planning_research/pm_wrapper/include/sbpl_pm_wrapper/pm_wrapper.h
===================================================================
--- pkg/trunk/motion_planning/planning_research/pm_wrapper/include/sbpl_pm_wrapper/pm_wrapper.h (rev 0)
+++ pkg/trunk/motion_planning/planning_research/pm_wrapper/include/sbpl_pm_wrapper/pm_wrapper.h 2009-08-24 23:57:09 UTC (rev 22791)
@@ -0,0 +1,100 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+/** \Author: Benjamin Cohen **/
+
+/**
+
+@mainpage
+
+A simple wrapper for the planning_monitor class in the planning_environment package. It's intended to be used by someone who wants to use a planning monitor for collision detection on a selective set of joints but doesn't want the other benefits of a planning monitor.
+
+This package is only temporary. I'll eventually replace it with a better solution.
+
+@htmlinclude manifest.html
+
+ **/
+
+#include <ros/ros.h>
+#include "ros/node_handle.h"
+#include <planning_environment/monitors/planning_monitor.h>
+#include <planning_environment/models/collision_models.h>
+#include <motion_planning_msgs/KinematicJoint.h>
+#include <motion_planning_msgs/GetMotionPlan.h>
+#include <planning_models/kinematic_state_params.h>
+
+
+namespace sbpl_arm_planner_node
+{
+ class pm_wrapper
+ {
+ public:
+
+ pm_wrapper();
+
+ ~pm_wrapper();
+
+ bool initPlanningMonitor(const std::vector<std::string> &links, tf::TransformListener * tfl);
+
+ bool areLinksValid(const double * angles);
+
+ void updatePM(const motion_planning_msgs::GetMotionPlan::Request &req);
+
+ void unlockPM();
+
+ private:
+
+ ros::NodeHandle node_;
+
+ ros::Subscriber col_map_subscriber_;
+
+ planning_models::StateParams *start_state_;
+
+ std::string arm_name_;
+
+ std::string robot_description_;
+
+ int groupID_;
+
+ std::string frame_;
+
+ std::vector<std::string> collision_check_links_;
+
+ planning_environment::CollisionModels *collision_model_;
+
+ planning_environment::PlanningMonitor *planning_monitor_;
+
+ planning_models::StateParams* fillStartState(const std::vector<motion_planning_msgs::KinematicJoint> &given);
+ };
+}
+
Modified: pkg/trunk/pr2/life_test/laser_tilt_test/life_test/controllers.xml
===================================================================
--- pkg/trunk/pr2/life_test/laser_tilt_test/life_test/controllers.xml 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/pr2/life_test/laser_tilt_test/life_test/controllers.xml 2009-08-24 23:57:09 UTC (rev 22791)
@@ -2,8 +2,41 @@
<controller name="laser_tilt_controller" topic="laser_controller" type="LaserScannerTrajControllerNode">
<max_acc value="1.0" />
<max_rate value="100.0" />
- <filter name="d_error_filter" type="TransferFunctionFilter">
- <params a="1.0 -.1" b=".9" />
+ <filter>
+ <struct>
+ <member>
+ <name>name</name>
+ <value><string>d_error_filter</string></value>
+ </member>
+ <member>
+ <name>type</name>
+ <value><string>TransferFunctionFilter</string></value>
+ </member>
+ <member>
+ <name>params</name>
+ <value>
+ <struct>
+ <member>
+ <name>a</name>
+ <value>
+ <array>
+ <value><double>1.0</double></value>
+ <value><double>-0.1</double></value>
+ </array>
+ </value>
+ </member>
+ <member>
+ <name>b</name>
+ <value>
+ <array>
+ <value><double>0.9</double></value>
+ </array>
+ </value>
+ </member>
+ </struct>
+ </value>
+ </member>
+ </struct>
</filter>
<joint name="laser_tilt_mount_joint">
<pid p="8" i=".1" d="0.2" iClamp="0.5" />
Modified: pkg/trunk/robot_descriptions/pr2/pr2_experimental_controllers/laser_tilt/laser_tilt_controller.xml
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_experimental_controllers/laser_tilt/laser_tilt_controller.xml 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/robot_descriptions/pr2/pr2_experimental_controllers/laser_tilt/laser_tilt_controller.xml 2009-08-24 23:57:09 UTC (rev 22791)
@@ -2,8 +2,47 @@
<controller name="laser_tilt_controller" topic="laser_controller" type="LaserScannerTrajControllerNode">
<max_acc value="1.0" />
<max_rate value="100.0" />
- <filter name="d_error_filter" type="TransferFunctionFilter">
- <params a="1.0 -.1" b=".9" />
+ <filter>
+ <value>
+ <struct>
+ <member>
+ <name>name</name>
+ <value>d_error_filter></value>
+ </member>
+ <member>
+ <name>type</name>
+ <value>TransferFunctionFilter</value>
+ </member>
+ <member>
+ <name>params</name>
+ <value>
+ <struct>
+ <member>
+ <name>a</name>
+ <value>
+ <array>
+ <data>
+ <value><double>1.0</double></value>
+ <value><double>-0.1</double></value>
+ </data>
+ </array>
+ </value>
+ </member>
+ <member>
+ <name>b</name>
+ <value>
+ <array>
+ <data>
+ <value><double>0.9</double></value>
+ </data>
+ </array>
+ </value>
+ </member>
+ </struct>
+ </value>
+ </member>
+ </struct>
+ </value>
</filter>
<joint name="laser_tilt_mount_joint">
<pid p="8" i=".1" d="0.2" iClamp="0.5" />
Added: pkg/trunk/sandbox/3dnav_pr2/ROS_BUILD_BLACKLIST
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/ROS_BUILD_BLACKLIST (rev 0)
+++ pkg/trunk/sandbox/3dnav_pr2/ROS_BUILD_BLACKLIST 2009-08-24 23:57:09 UTC (rev 22791)
@@ -0,0 +1 @@
+broken see ticket https://prdev.willowgarage.com/trac/personalrobots/ticket/2516
Modified: pkg/trunk/sandbox/3dnav_pr2/launch/perception/laser+stereo-perception.launch
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/launch/perception/laser+stereo-perception.launch 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/sandbox/3dnav_pr2/launch/perception/laser+stereo-perception.launch 2009-08-24 23:57:09 UTC (rev 22791)
@@ -12,7 +12,7 @@
<!-- convert laser scan to pointcloud -->
<node machine="three" pkg="laser_scan" type="scan_to_cloud" output="screen">
<param name="scan_topic" type="string" value="tilt_scan" />
- <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
+ <rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
<param name="high_fidelity" type="bool" value="true" />
<param name="cloud_topic" type="string" value="tilt_scan_cloud" />
</node>
Modified: pkg/trunk/sandbox/3dnav_pr2/launch/perception/laser-perception.launch
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/launch/perception/laser-perception.launch 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/sandbox/3dnav_pr2/launch/perception/laser-perception.launch 2009-08-24 23:57:09 UTC (rev 22791)
@@ -12,7 +12,7 @@
<!-- convert tilt laser scan to pointcloud -->
<node machine="three" pkg="laser_scan" type="scan_to_cloud" output="screen" name="scan_to_cloud_tilt_laser">
<param name="scan_topic" type="string" value="tilt_scan" />
- <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
+ <rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
<param name="cloud_topic" type="string" value="tilt_scan_cloud" />
</node>
Modified: pkg/trunk/sandbox/annotated_map_builder/config/perception.xml
===================================================================
--- pkg/trunk/sandbox/annotated_map_builder/config/perception.xml 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/sandbox/annotated_map_builder/config/perception.xml 2009-08-24 23:57:09 UTC (rev 22791)
@@ -34,8 +34,8 @@
<!-- Filter for tilt laser shadowing/veiling -->
<node pkg="laser_scan" type="scan_to_cloud" respawn="true" machine="three" name="tilt_shadow_filter">
- <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
- <param name="cloud_filters" textfile="$(find laser_scan)/point_cloud_footprint.filters.xml" />
+ <rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
+ <rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="tilt_scan" />
<param name="cloud_topic" value="tilt_scan_filtered" />
<param name="high_fidelity" value="true" />
@@ -43,8 +43,8 @@
<!-- Filter for base laser shadowing/veiling -->
<node pkg="laser_scan" type="scan_to_cloud" respawn="true" machine="three" name="base_shadow_filter" >
- <param name="scan_filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
- <param name="cloud_filters" textfile="$(find laser_scan)/point_cloud_footprint.filters.xml" />
+ <rosparam command="load" ns="scan_filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
+ <rosparam command="load" ns="cloud_filters" file="$(find laser_scan)/point_cloud_footprint.filters.yaml" />
<param name="scan_topic" value="base_scan" />
<param name="cloud_topic" value="base_scan_marking" />
</node>
@@ -52,7 +52,7 @@
<!-- Laser scan assembler for tilt laser -->
<node pkg="point_cloud_assembler" type="laser_scan_assembler_srv" output="screen" name="laser_scan_assembler" respawn="true">
<remap from="scan_in" to="tilt_scan"/>
- <param name="filters" textfile="$(find laser_scan)/default_scan_shadows.xml" />
+ <rosparam command="load" ns="filters" file="$(find laser_scan)/default_scan_shadows.yaml" />
<param name="tf_cache_time_secs" type="double" value="10.0" />
<param name="max_scans" type="int" value="1000" />
<param name="ignore_laser_skew" type="bool" value="true" />
Modified: pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/cartesian_hybrid_controller.h
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/cartesian_hybrid_controller.h 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/cartesian_hybrid_controller.h 2009-08-24 23:57:09 UTC (rev 22791)
@@ -95,7 +95,7 @@
double saturated_velocity_, saturated_rot_velocity_;
bool use_filter_;
- filters::FilterChain<double> twist_filter_;
+ filters::MultiChannelFilterChain<double> twist_filter_;
ros::NodeHandle node_;
};
Modified: pkg/trunk/sandbox/experimental_controllers/src/cartesian_hybrid_controller.cpp
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/src/cartesian_hybrid_controller.cpp 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/sandbox/experimental_controllers/src/cartesian_hybrid_controller.cpp 2009-08-24 23:57:09 UTC (rev 22791)
@@ -78,7 +78,7 @@
}
CartesianHybridController::CartesianHybridController()
- : robot_(NULL), last_time_(0), use_filter_(false)
+ : robot_(NULL), last_time_(0), use_filter_(false), twist_filter_("double")
{
}
@@ -163,20 +163,18 @@
if (node_.hasParam("twist_filter"))
{
use_filter_ = true;
+
+ // \TODO remove when ticket https://prdev.willowgarage.com/trac/personalrobots/ticket/2575 is resolved
std::string filter_xml;
node_.getParam("twist_filter", filter_xml);
-
- TiXmlDocument doc;
- doc.Parse(filter_xml.c_str());
- if (!doc.RootElement())
- {
- ROS_ERROR("Could not parse twist_filter xml (namespace: %s)",
- node_.getNamespace().c_str());
+ int offset = 0;
+ XmlRpc::XmlRpcValue filter_xmlrpc(filter_xml, &offset);
+ if (!twist_filter_.configure(6, filter_xmlrpc))
return false;
- }
-
- if (!twist_filter_.configure(6, doc.RootElement()))
+ /* Replace with below
+ if (!twist_filter_.configure(6, "twist_filter", node_))
return false;
+ end Replace */
ROS_INFO("Successfully configured twist_filter (namespace: %s)",
node_.getNamespace().c_str());
}
Added: pkg/trunk/sandbox/joint_waypoint_controller/ROS_BUILD_BLACKLIST
===================================================================
--- pkg/trunk/sandbox/joint_waypoint_controller/ROS_BUILD_BLACKLIST (rev 0)
+++ pkg/trunk/sandbox/joint_waypoint_controller/ROS_BUILD_BLACKLIST 2009-08-24 23:57:09 UTC (rev 22791)
@@ -0,0 +1 @@
+broken see ticket https://prdev.willowgarage.com/trac/personalrobots/ticket/2516
Added: pkg/trunk/sandbox/spline_smoother/ROS_BUILD_BLACKLIST
===================================================================
--- pkg/trunk/sandbox/spline_smoother/ROS_BUILD_BLACKLIST (rev 0)
+++ pkg/trunk/sandbox/spline_smoother/ROS_BUILD_BLACKLIST 2009-08-24 23:57:09 UTC (rev 22791)
@@ -0,0 +1 @@
+broken see ticket https://prdev.willowgarage.com/trac/personalrobots/ticket/2516
Added: pkg/trunk/sandbox/trajectory_controllers/ROS_BUILD_BLACKLIST
===================================================================
--- pkg/trunk/sandbox/trajectory_controllers/ROS_BUILD_BLACKLIST (rev 0)
+++ pkg/trunk/sandbox/trajectory_controllers/ROS_BUILD_BLACKLIST 2009-08-24 23:57:09 UTC (rev 22791)
@@ -0,0 +1 @@
+broken see ticket https://prdev.willowgarage.com/trac/personalrobots/ticket/2516
Modified: pkg/trunk/stacks/common/filters/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/common/filters/CMakeLists.txt 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/stacks/common/filters/CMakeLists.txt 2009-08-24 23:57:09 UTC (rev 22791)
@@ -1,28 +1,40 @@
cmake_minimum_required(VERSION 2.4.6)
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
-rospack(filters)
+rosbuild_init()
-rospack_add_boost_directories()
+rosbuild_add_boost_directories()
-rospack_add_library(filter
- src/transfer_function.cpp)
+#Plugins
+rosbuild_add_library(mean src/mean.cpp)
+rosbuild_add_library(median src/median.cpp)
+rosbuild_add_library(transfer_function src/transfer_function.cpp)
-rospack_add_gtest(median_test test/test_median.cpp)
-target_link_libraries(median_test loki)
+# Test median filter
+rosbuild_add_executable(median_test test/test_median.cpp)
+target_link_libraries(median_test median)
+rosbuild_declare_test(median_test)
+rosbuild_add_gtest_build_flags(median_test)
+rosbuild_add_rostest(test/test_median.launch)
-# broken, needs to go to the new form factor
-rospack_add_gtest(transfer_function_test test/test_transfer_function.cpp)
-rospack_add_link_flags(transfer_function_test "-lloki")
+#test transfer function filter
+rosbuild_add_executable(transfer_function_test test/test_transfer_function.cpp)
+target_link_libraries(transfer_function_test transfer_function)
+rosbuild_declare_test(transfer_function_test)
+rosbuild_add_gtest_build_flags(transfer_function_test)
+rosbuild_add_rostest(test/test_transfer_function.launch)
+#test mean filter
+rosbuild_add_executable(mean_test test/test_mean.cpp)
+target_link_libraries(mean_test mean)
+rosbuild_declare_test(mean_test)
+rosbuild_add_gtest_build_flags(mean_test)
+rosbuild_add_rostest(test/test_mean.launch)
-rospack_add_gtest(mean_test test/test_mean.cpp)
-target_link_libraries(mean_test loki)
+#Test plugin loading into filter chain
+rosbuild_add_executable(chain_test test/test_chain.cpp)
+rosbuild_declare_test(chain_test)
+rosbuild_add_gtest_build_flags(chain_test)
+rosbuild_add_rostest(test/test_chain.launch)
-rospack_add_gtest(factory_test test/test_factory.cpp)
-target_link_libraries(factory_test loki)
-
-rospack_add_gtest(chain_test test/test_chain.cpp)
-target_link_libraries(chain_test loki)
-
-rospack_add_gtest(realtime_buffer_test test/test_realtime_circular_buffer.cpp)
-target_link_libraries(realtime_buffer_test loki)
+# Test reltime safe buffer class
+rosbuild_add_gtest(realtime_buffer_test test/test_realtime_circular_buffer.cpp)
Added: pkg/trunk/stacks/common/filters/default_plugins.xml
===================================================================
--- pkg/trunk/stacks/common/filters/default_plugins.xml (rev 0)
+++ pkg/trunk/stacks/common/filters/default_plugins.xml 2009-08-24 23:57:09 UTC (rev 22791)
@@ -0,0 +1,62 @@
+<class_libraries>
+ <library path="lib/libmedian">
+ <class name="MultiChannelMedianFilterDouble" type="filters::MultiChannelMedianFilter<double>"
+ base_class_type="filters::MultiChannelFilterBase<double>">
+ <description>
+ THis is a median filter which works on a stream of std::vector of doubles.
+ </description>
+ </class>
+ <class name="MedianFilterDouble" type="filters::MedianFilter<double>"
+ base_class_type="filters::FilterBase<double>">
+ <description>
+ THis is a median filter which works on a stream of doubles.
+ </description>
+ </class>
+ <class name="MultiChannelMedianFilterFloat" type="filters::MultiChannelMedianFilter<float>"
+ base_class_type="filters::MultiChannelFilterBase<float>">
+ <description>
+ THis is a median filter which works on a stream of std::vector of floats.
+ </description>
+ </class>
+ <class name="MedianFilterFloat" type="filters::MedianFilter<float>"
+ base_class_type="filters::FilterBase<float>">
+ <description>
+ THis is a median filter which works on a stream of floats.
+ </description>
+ </class>
+ </library>
+ <library path="lib/libmean">
+ <class name="MeanFilterDouble" type="filters::MeanFilter<double>"
+ base_class_type="filters::FilterBase<double>">
+ <description>
+ THis is a mean filter which works on a stream of doubles.
+ </description>
+ </class>
+ <class name="MeanFilterFloat" type="filters::MeanFilter<float>"
+ base_class_type="filters::FilterBase<float>">
+ <description>
+ THis is a mean filter which works on a stream of floats.
+ </description>
+ </class>
+ <class name="MultiChannelMeanFilterDouble" type="filters::MultiChannelMeanFilter<double>"
+ base_class_type="filters::MultiChannelFilterBase<double>">
+ <description>
+ THis is a mean filter which works on a stream of vectors of doubles.
+ </description>
+ </class>
+ <class name="MultiChannelMeanFilterFloat" type="filters::MultiChannelMeanFilter<float>"
+ base_class_type="filters::MultiChannelFilterBase<float>">
+ <description>
+ THis is a mean filter which works on a stream of vectors of floats.
+ </description>
+ </class>
+ </library>
+ <library path="lib/libtransfer_function">
+ <class name="transferFunctionMultiDouble" type="filters::TransferFunctionDoubleFilter"
+ base_class_type="filters::MultiChannelFilterBase<double>">
+ <description>
+ THis is a transfer filter which works on a stream of doubles.
+ </description>
+ </class>
+ </library>
+</class_libraries>
Modified: pkg/trunk/stacks/common/filters/include/filters/filter_base.h
===================================================================
--- pkg/trunk/stacks/common/filters/include/filters/filter_base.h 2009-08-24 23:54:35 UTC (rev 22790)
+++ pkg/trunk/stacks/common/filters/include/filters/filter_base.h 2009-08-24 23:57:09 UTC (rev 22791)
@@ -30,11 +30,10 @@
#ifndef FILTERS_FILTER_BASE_H_
#define FILTERS_FILTER_BASE_H_
-#include <tinyxml/tinyxml.h>
#include <typeinfo>
-#include <loki/Factory.h>
#include "ros/assert.h"
#include "ros/console.h"
+#include "ros/ros.h"
#include "boost/scoped_ptr.hpp"
#include <boost/algorithm/string.hpp>
@@ -42,18 +41,8 @@
namespace filters
{
-typedef std::map<std::string, std::string> string_map_t;
+typedef std::map<std::string, XmlRpc::XmlRpcValue> string_map_t;
-template <typename T>
-std::string getFilterID(const std::string & filter_name)
-{
- return filter_name + typeid(T).name();
-
-}
-
-
-
-
/** \brief A Base filter class to provide a standard interface for all filters
*
*/
@@ -63,56 +52,55 @@
public:
/** \brief Default constructor used by Filter Factories
*/
- FilterBase():number_of_channels_(0), configured_(false){};
+ FilterBase():configured_(false){};
/** \brief Virtual Destructor
*/
virtual ~FilterBase(){};
+ /** \brief Configure the filter from the parameter server
+ * \param The parameter from which to read the configuration
+ * \param node_handle The optional node handle, useful if operating in a different namespace.
+ */
+ bool configure(const std::string& param_name, ros::NodeHandle node_handle = ros::NodeHandle())
+ {
+ XmlRpc::XmlRpcValue config;
+ if (!node_handle.getParam(param_name, config))
+ {
+ ROS_ERROR("Could not find parameter %s on the server, are you sure that it was pushed up correctly?", param_name.c_str());
+ return false;
+ }
+ return configure(config);
+
+ }
+
/** \brief The public method to configure a filter from XML
- * \param number_of_channels How many parallel channels the filter will process
- * \param config The XML to initialize the filter with including name, type, and any parameters
+ * \param config The XmlRpcValue from which the filter should be initialized
*/
- bool configure(unsigned int number_of_channels, TiXmlElement *config)
+ bool configure(XmlRpc::XmlRpcValue& config)
{
if (configured_)
{
ROS_WARN("Filter %s of type %s already being reconfigured", filter_name_.c_str(), filter_type_.c_str());
};
configured_ = false;
- number_of_channels_ = number_of_channels;
bool retval = true;
- retval = retval && loadXml(config);
+ retval = retval && loadCon...
[truncated message content] |