ObstacleProviderControllerOptions.cpp
Go to the documentation of this file.
00001 /*
00002  * ObstacleProviderControllerOptions.cpp
00003  *
00004  *  Created on: Dec 14, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #include <obs_detection/ObstacleProviderControllerOptions.hpp>
00009 
00010 namespace TELEKYB_NAMESPACE {
00011 
00012 ObstacleProviderControllerOptions::ObstacleProviderControllerOptions()
00013         : OptionContainer("ObstacleProviderController")
00014 {
00015         tObsSpinrate = addBoundsOption<double>("tObsSpinrate",
00016                         "Specifies the rate at which the Controller collects Obstacles from Providers", 30.0, 0.0, 240.0, false, true);
00017 
00018         std::vector<std::string> defaultObstacleProviders;
00019         defaultObstacleProviders.push_back("tk_obstacle/SurroundingBox");
00020         //defaultObstacleProviders.push_back("tk_trajprocessor/XMModeCheck");
00021 
00022         tObstacleProviders = addOption("tObstacleProviders", "List of tObstacle Providers Plugins to load.",
00023                         defaultObstacleProviders, false, true);
00024         tTKStateTopicName = addOption<std::string>("tTKStateTopicName", "Topic Name of Robots TKState",
00025                         "undef", true, true);
00026         tObsPubTopicName = addOption<std::string>("tObsPubTopicName", "Topic Name of Obstacle Points",
00027                         "ObstaclePoints", false, true);
00028         tInitialStateTimeout = addBoundsOption<double>("tInitialStateTimeout",
00029                                                         "Specify the time to wait for the initial TKState Message.", 5.0, 0.0, 20.0, false, true);
00030 
00031 }
00032 
00033 
00034 } /* namespace telekyb */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


tk_obstacle
Author(s): Martin Riedel
autogenerated on Mon Nov 11 2013 11:13:22