$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id: test_observers.cpp 689 2012-04-20 06:42:17Z xlokaj03 $ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by Robo@FIT group. 00009 * 00010 * Author: Tomas Lokaj (xlokaj03@stud.fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: 25/1/2012 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 00028 #include <ros/ros.h> 00029 #include <visualization_msgs/InteractiveMarker.h> 00030 #include <visualization_msgs/InteractiveMarkerUpdate.h> 00031 #include <std_msgs/String.h> 00032 #include <srs_interaction_primitives/ScaleChanged.h> 00033 #include <srs_interaction_primitives/PoseChanged.h> 00034 #include <srs_interaction_primitives/MenuClicked.h> 00035 #include <srs_interaction_primitives/MovementChanged.h> 00036 #include <srs_interaction_primitives/TagChanged.h> 00037 //#include <srs_env_model/ContextChanged.h> 00038 #include <srs_interaction_primitives/MoveArmToPreGrasp.h> 00039 00040 using namespace std; 00041 00046 void scaleCallback(const srs_interaction_primitives::ScaleChangedConstPtr &marker_update) 00047 { 00048 ROS_INFO("CALLBACK from marker %s", marker_update->marker_name.c_str()); 00049 cout << marker_update->scale_change << endl; 00050 cout << marker_update->new_scale << endl; 00051 } 00052 00053 void poseCallback(const srs_interaction_primitives::PoseChangedConstPtr &marker_update) 00054 { 00055 ROS_INFO("CALLBACK from marker %s", marker_update->marker_name.c_str()); 00056 cout << marker_update->pose_change << endl; 00057 cout << marker_update->new_pose << endl; 00058 } 00059 00060 void menuCallback(const srs_interaction_primitives::MenuClickedConstPtr &marker_update) 00061 { 00062 ROS_INFO("CALLBACK from marker %s", marker_update->marker_name.c_str()); 00063 cout << marker_update->menu_title << endl; 00064 cout << marker_update->state << endl; 00065 } 00066 00067 void movementCallback(const srs_interaction_primitives::MovementChangedConstPtr &marker_update) 00068 { 00069 ROS_INFO("CALLBACK from marker %s", marker_update->marker_name.c_str()); 00070 cout << marker_update->direction_change << endl; 00071 cout << marker_update->velocity_change << endl; 00072 cout << marker_update->new_direction << endl; 00073 cout << marker_update->new_velocity << endl; 00074 } 00075 00076 void tagCallback(const srs_interaction_primitives::TagChangedConstPtr &marker_update) 00077 { 00078 ROS_INFO("CALLBACK from marker %s", marker_update->marker_name.c_str()); 00079 cout << marker_update->new_tag << endl; 00080 } 00081 00082 /*void contextCallback(const srs_interaction_primitives::ContextChangedConstPtr &context_update) 00083 { 00084 ROS_INFO("Context changed"); 00085 cout << context_update->context << endl; 00086 }*/ 00087 00088 void pregraspCallback(const srs_interaction_primitives::MoveArmToPreGraspConstPtr &update) 00089 { 00090 ROS_INFO("Move arm to pre-grasp clicked"); 00091 cout << update->marker_name << endl; 00092 cout << (int)update->pos_id << endl; 00093 } 00094 00095 int main(int argc, char** argv) 00096 { 00097 ros::init(argc, argv, "test_observers"); 00098 ros::NodeHandle n; 00099 00100 ros::Subscriber sub1 = n.subscribe<srs_interaction_primitives::ScaleChanged> ("/interaction_primitives/unknown_object/update/scale_changed", 20, 00101 scaleCallback); 00102 ros::Subscriber sub2 = n.subscribe<srs_interaction_primitives::PoseChanged> ("/interaction_primitives/unknown_object/update/pose_changed", 20, 00103 poseCallback); 00104 ros::Subscriber sub3 = n.subscribe<srs_interaction_primitives::ScaleChanged> ("/interaction_primitives/person_bbox/update/scale_changed", 20, 00105 scaleCallback); 00106 ros::Subscriber sub4 = n.subscribe<srs_interaction_primitives::PoseChanged> ("/interaction_primitives/person_bbox/update/pose_changed", 20, 00107 poseCallback); 00108 ros::Subscriber sub5 = n.subscribe<srs_interaction_primitives::ScaleChanged> ("/interaction_primitives/table_object/update/scale_changed", 20, 00109 scaleCallback); 00110 ros::Subscriber sub6 = n.subscribe<srs_interaction_primitives::PoseChanged> ("/interaction_primitives/table_object/update/pose_changed", 20, 00111 poseCallback); 00112 00113 ros::Subscriber subm1 = n.subscribe<srs_interaction_primitives::MenuClicked> ("/interaction_primitives/table_object/update/menu_clicked", 20, 00114 menuCallback); 00115 ros::Subscriber subm2 = n.subscribe<srs_interaction_primitives::MenuClicked> ("/interaction_primitives/person_bbox/update/menu_clicked", 20, 00116 menuCallback); 00117 ros::Subscriber subm3 = n.subscribe<srs_interaction_primitives::MenuClicked> ("/interaction_primitives/unknown_object/update/menu_clicked", 20, 00118 menuCallback); 00119 ros::Subscriber subm4 = n.subscribe<srs_interaction_primitives::MenuClicked> ("/interaction_primitives/milk_billboard/update/menu_clicked", 20, 00120 menuCallback); 00121 ros::Subscriber subm5 = n.subscribe<srs_interaction_primitives::MenuClicked> ("/interaction_primitives/plane1/update/menu_clicked", 20, 00122 menuCallback); 00123 00124 ros::Subscriber submovement = 00125 n.subscribe<srs_interaction_primitives::MovementChanged> ("/interaction_primitives/milk_billboard/update/movement_changed", 20, 00126 movementCallback); 00127 00128 ros::Subscriber tag = n.subscribe<srs_interaction_primitives::TagChanged> ("/interaction_primitives/plane/update/tag_changed", 20, tagCallback); 00129 00130 ros::Subscriber milk1 = n.subscribe<srs_interaction_primitives::MenuClicked> ("/interaction_primitives/milk/update/menu_clicked", 20, 00131 menuCallback); 00132 ros::Subscriber milk2 = n.subscribe<srs_interaction_primitives::PoseChanged> ("/interaction_primitives/milk/update/pose_changed", 20, 00133 poseCallback); 00134 ros::Subscriber milk3 = n.subscribe<srs_interaction_primitives::ScaleChanged> ("/interaction_primitives/milk/update/scale_changed", 20, 00135 scaleCallback); 00136 00137 // Test context changes 00138 //ros::Subscriber context = n.subscribe<srs_env_model::ContextChanged> ("but_context/context_changed", 20, contextCallback); 00139 00140 // Test move arm to pre-grasp 00141 ros::Subscriber 00142 pregrasp = 00143 n.subscribe<srs_interaction_primitives::MoveArmToPreGrasp> ("interaction_primitives/object/update/move_arm_to_pregrasp", 20, 00144 pregraspCallback); 00145 00146 ros::spin(); 00147 } 00148