00001 /**** 00002 This is part of the Retalis Language for Information Processing and Management in Robotics 00003 Copyright (C) 2014 __Pouyan Ziafati__ pziafati@gmail.com 00004 00005 Retalis is free software: you can redistribute it and/or modify 00006 it under the terms of the GNU General Public License as published by 00007 the Free Software Foundation, either version 3 of the License, or 00008 (at your option) any later version. 00009 00010 Retalis is distributed in the hope that it will be useful, 00011 but WITHOUT ANY WARRANTY; without even the implied warranty of 00012 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00013 GNU General Public License for more details. 00014 00015 You should have received a copy of the GNU General Public License 00016 along with Retalis. If not, see <http://www.gnu.org/licenses/>. 00017 ****/ 00018 00019 #include "ros/ros.h" 00020 #include "std_msgs/String.h" 00021 #include "SWI-cpp.h" 00022 00023 00024 ros::NodeHandle n; 00025 ros::Publisher outputEventsPub_; 00026 00031 PREDICATE(retalis_output_initialize, 1) 00032 { 00033 outputEventsPub_ = n.advertise<std_msgs::String>("retalisOutputEvents", 5000); 00034 return TRUE; 00035 } 00036 00037 00038 PREDICATE(output_to_ros, 1) 00039 { 00040 //ROS_INFO("***** %s",(char *) A1); 00041 std_msgs::String event; 00042 event.data = (char *) A1; 00043 outputEventsPub_.publish(event); 00044 return TRUE; 00045 } 00046 00047