Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008 #include <telekyb_base/ROS/ROSOptionContainer.hpp>
00009
00010 #include <telekyb_base/Options/OptionContainer.hpp>
00011
00012 namespace TELEKYB_NAMESPACE
00013 {
00014
00015 ROSOptionContainer::ROSOptionContainer(OptionContainer* optionContainer_)
00016 : optionContainer(optionContainer_)
00017 {
00018
00019 }
00020
00021 ROSOptionContainer::~ROSOptionContainer() {
00022
00023 }
00024
00025
00026
00027 void ROSOptionContainer::createGetService() {
00028
00029 if (!ROSOptionController::hasInstance()) {
00030 ROS_ERROR_STREAM("createSetService() called on ROSOptionContainer "
00031 << optionContainer->getOptionContainerNamespace() << ", ROSOptionController is not initialized yet.");
00032 return;
00033 }
00034 ros::NodeHandle serviceHandle(ROSOptionController::Instance().getOptionNodeHandle(), optionContainer->getOptionContainerNamespace());
00035 getService = serviceHandle.advertiseService(OPTION_GETSERVICE_NAME, &ROSOptionContainer::getServiceCallBack, this);
00036 }
00037
00038
00039 void ROSOptionContainer::createSetService() {
00040
00041 if (!ROSOptionController::hasInstance()) {
00042 ROS_ERROR_STREAM("createSetService() called on ROSOptionContainer "
00043 << optionContainer->getOptionContainerNamespace() << ", ROSOptionController is not initialized yet.");
00044 return;
00045 }
00046 ros::NodeHandle serviceHandle(ROSOptionController::Instance().getOptionNodeHandle(), optionContainer->getOptionContainerNamespace());
00047 setService = serviceHandle.advertiseService(OPTION_SETSERVICE_NAME, &ROSOptionContainer::setServiceCallBack, this);
00048 }
00049
00050 void ROSOptionContainer::shutdownGetService() {
00051 getService.shutdown();
00052 }
00053
00054 void ROSOptionContainer::shutdownSetService() {
00055 setService.shutdown();
00056 }
00057
00058
00059 bool ROSOptionContainer::getServiceCallBack(
00060 telekyb_srvs::StringOutput::Request& request,
00061 telekyb_srvs::StringOutput::Response& response)
00062 {
00063
00064 YAML::Node node;
00065 optionContainer->get(node);
00066 return YamlHelper::parseNodeToString(node, response.output);
00067 }
00068
00069 bool ROSOptionContainer::setServiceCallBack(
00070 telekyb_srvs::StringInput::Request& request,
00071 telekyb_srvs::StringInput::Response& response)
00072 {
00073
00074 YAML::Node node;
00075 YamlHelper::parseStringToNode(request.input, node);
00076 optionContainer->set(node);
00077
00078 return true;
00079 }
00080
00081 }