$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id: Billboard.cpp 676 2012-04-19 18:32:07Z 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: 27/11/2011 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 <srs_interaction_primitives/billboard.h> 00029 00030 using namespace std; 00031 using namespace interactive_markers; 00032 using namespace visualization_msgs; 00033 using namespace geometry_msgs; 00034 using namespace std_msgs; 00035 00036 namespace srs_interaction_primitives 00037 { 00038 00039 Billboard::Billboard(InteractiveMarkerServerPtr server, string frame_id, string name) : 00040 Primitive(server, frame_id, name, srs_interaction_primitives::PrimitiveType::BILLBOARD) 00041 { 00042 velocity_ = 0.0; 00043 color_.r = 0; 00044 color_.g = 0; 00045 color_.b = 1; 00046 color_.a = 1; 00047 } 00048 00049 void Billboard::menuCallback(const InteractiveMarkerFeedbackConstPtr &feedback) 00050 { 00051 MenuHandler::EntryHandle handle = feedback->menu_entry_id; 00052 MenuHandler::CheckState state; 00053 string title; 00054 menu_handler_.getCheckState(handle, state); 00055 menu_handler_.getTitle(handle, title); 00056 00057 updatePublisher_->publishMenuClicked(title, state); 00058 00059 switch (feedback->menu_entry_id) 00060 { 00061 case 1: 00062 /* 00063 * Billboard trajectory 00064 */ 00065 if (state == MenuHandler::CHECKED) 00066 { 00067 removeTrajectoryControls(); 00068 menu_handler_.setCheckState(handle, MenuHandler::UNCHECKED); 00069 } 00070 else 00071 { 00072 addTrajectoryControls(); 00073 menu_handler_.setCheckState(handle, MenuHandler::CHECKED); 00074 } 00075 break; 00076 case 2: 00077 /* 00078 * Billboard trajectory prediction 00079 */ 00080 if (state == MenuHandler::CHECKED) 00081 { 00082 removeTrajectoryPredictionMarkers(); 00083 menu_handler_.setCheckState(handle, MenuHandler::UNCHECKED); 00084 } 00085 else 00086 { 00087 addTrajectoryPredictionMarkers(); 00088 menu_handler_.setCheckState(handle, MenuHandler::CHECKED); 00089 } 00090 break; 00091 case 3: 00092 /* 00093 * Billboard description 00094 */ 00095 if (state == MenuHandler::CHECKED) 00096 { 00097 removeDescriptionControl(); 00098 menu_handler_.setCheckState(handle, MenuHandler::UNCHECKED); 00099 } 00100 else 00101 { 00102 addDescriptionControl(); 00103 menu_handler_.setCheckState(handle, MenuHandler::CHECKED); 00104 } 00105 break; 00106 } 00107 00108 server_->insert(object_); 00109 menu_handler_.reApply(*server_); 00110 server_->applyChanges(); 00111 } 00112 00113 void Billboard::setType(int type) 00114 { 00115 billboard_type_ = type; 00116 } 00117 00118 int Billboard::getType() 00119 { 00120 return billboard_type_; 00121 } 00122 00123 void Billboard::updateControls() 00124 { 00125 if (show_trajectory_control_) 00126 { 00127 removeTrajectoryControls(); 00128 addTrajectoryControls(); 00129 } 00130 Primitive::updateControls(); 00131 } 00132 00133 void Billboard::removeTrajectoryControls() 00134 { 00135 show_trajectory_control_ = false; 00136 removeControl("trajectory_control"); 00137 } 00138 00139 void Billboard::addTrajectoryControls() 00140 { 00141 show_trajectory_control_ = true; 00142 00143 trajectoryControl_.markers.clear(); 00144 00145 trajectoryControl_.name = "trajectory_control"; 00146 trajectoryControl_.always_visible = true; 00147 trajectoryControl_.orientation_mode = InteractiveMarkerControl::FIXED; 00148 00149 if (velocity_ != 0.0) 00150 { 00151 Marker trajectoryArrow; 00152 trajectoryArrow.type = Marker::ARROW; 00153 trajectoryArrow.pose.position.x = 0; 00154 trajectoryArrow.pose.position.y = 0; 00155 trajectoryArrow.pose.position.z = 0; 00156 trajectoryArrow.pose.orientation = direction_; 00157 trajectoryArrow.scale.x = 0.25; 00158 trajectoryArrow.scale.y = 0.25; 00159 trajectoryArrow.scale.z = velocity_; 00160 trajectoryArrow.color.r = 1.0; 00161 trajectoryArrow.color.g = 0.0; 00162 trajectoryArrow.color.b = 0.0; 00163 trajectoryArrow.color.a = 1.0; 00164 trajectoryControl_.markers.push_back(trajectoryArrow); 00165 } 00166 00167 ostringstream velocityText; 00168 velocityText << setprecision(2) << fixed << velocity_ << "m/s"; 00169 Marker trajectoryText; 00170 trajectoryText.type = Marker::TEXT_VIEW_FACING; 00171 trajectoryText.text = velocityText.str(); 00172 trajectoryText.scale.z = 0.2; 00173 trajectoryText.color.r = 1.0; 00174 trajectoryText.color.g = 0.0; 00175 trajectoryText.color.b = 0.0; 00176 trajectoryText.color.a = 1.0; 00177 trajectoryText.pose.position.x = 0.0; 00178 trajectoryText.pose.position.y = 0.0; 00179 trajectoryText.pose.position.z = 0.0; 00180 trajectoryControl_.markers.push_back(trajectoryText); 00181 00182 object_.controls.push_back(trajectoryControl_); 00183 } 00184 00185 void Billboard::createMenu() 00186 { 00187 if (!menu_created_) 00188 { 00189 menu_created_ = true; 00190 menu_handler_.setCheckState( 00191 menu_handler_.insert("Show trajectory", boost::bind(&Billboard::menuCallback, this, _1)), 00192 MenuHandler::UNCHECKED); 00193 menu_handler_.setCheckState( 00194 menu_handler_.insert("Show trajectory prediction", boost::bind(&Billboard::menuCallback, this, _1)), 00195 MenuHandler::UNCHECKED); 00196 menu_handler_.setCheckState( 00197 menu_handler_.insert("Show description", boost::bind(&Billboard::menuCallback, this, _1)), 00198 MenuHandler::UNCHECKED); 00199 } 00200 00201 } 00202 00203 void Billboard::createMesh() 00204 { 00205 mesh_.type = Marker::MESH_RESOURCE; 00206 mesh_.mesh_use_embedded_materials = true; 00207 mesh_.scale.y = scale_.x; 00208 mesh_.scale.z = scale_.y; 00209 // Model flip 00210 mesh_.pose.orientation.x = 180; 00211 00212 if (billboard_type_ == BillboardType::CHAIR) 00213 mesh_.mesh_resource = "package://srs_interaction_primitives/meshes/chair.dae"; 00214 else if (billboard_type_ == BillboardType::MILK) 00215 mesh_.mesh_resource = "package://srs_interaction_primitives/meshes/milk.dae"; 00216 else if (billboard_type_ == BillboardType::TABLE) 00217 mesh_.mesh_resource = "package://srs_interaction_primitives/meshes/table.dae"; 00218 else if (billboard_type_ == BillboardType::PERSON) 00219 mesh_.mesh_resource = "package://srs_interaction_primitives/meshes/person.dae"; 00220 else if (billboard_type_ == BillboardType::PERSON_HEAD) 00221 mesh_.mesh_resource = "package://srs_interaction_primitives/meshes/person_head.dae"; 00222 else 00223 ROS_ERROR("UNKNOWN BILLBOARD TYPE!"); 00224 } 00225 00226 void Billboard::addTrajectoryPredictionMarkers() 00227 { 00228 visualization_msgs::InteractiveMarker predictionMarker; 00229 predictionMarker = object_; 00230 predictionMarker.controls.clear(); 00231 00232 Ogre::Matrix3 *rotation = new Ogre::Matrix3(); 00233 Ogre::Quaternion orientation; 00234 orientation.x = direction_.x; 00235 orientation.y = direction_.y; 00236 orientation.z = direction_.z; 00237 orientation.w = direction_.w; 00238 orientation.normalise(); 00239 orientation.ToRotationMatrix(*rotation); 00240 Ogre::Vector3 position; 00241 position.x = velocity_; 00242 position.y = 0; 00243 position.z = 0; 00244 position = rotation->operator *(position); 00245 00246 predictionMarker.pose.position.x = pose_.position.x; 00247 predictionMarker.pose.position.y = pose_.position.y; 00248 predictionMarker.pose.position.z = pose_.position.z; 00249 00250 visualization_msgs::InteractiveMarkerControl predictionControl; 00251 predictionControl.name = "prediction_control"; 00252 predictionControl.always_visible = true; 00253 predictionControl.orientation_mode = InteractiveMarkerControl::VIEW_FACING; 00254 predictionControl.interaction_mode = InteractiveMarkerControl::NONE; 00255 00256 for (int i = 1; i < PREDICTIONS_COUNT + 1; i++) 00257 { 00258 std::stringstream name; 00259 name << name_ << "_prediction_" << i; 00260 predictionMarker.name = name.str(); 00261 std::stringstream desc; 00262 desc << i << "s"; 00263 predictionMarker.description = desc.str(); 00264 predictionMarker.pose.position.x += position.x; 00265 predictionMarker.pose.position.y += position.y; 00266 predictionMarker.pose.position.z += position.z; 00267 00268 predictionControl.markers.clear(); 00269 predictionMarker.controls.clear(); 00270 00271 visualization_msgs::Marker sphere; 00272 sphere.type = visualization_msgs::Marker::SPHERE; 00273 sphere.color.g = 1; 00274 sphere.color.b = 1; 00275 sphere.color.a = 1; 00276 sphere.scale.x = PREDICTION_SPHERE_SIZE; 00277 sphere.scale.y = PREDICTION_SPHERE_SIZE; 00278 sphere.scale.z = PREDICTION_SPHERE_SIZE; 00279 00280 predictionControl.markers.push_back(sphere); 00281 predictionMarker.controls.push_back(predictionControl); 00282 00283 server_->insert(predictionMarker); 00284 } 00285 server_->applyChanges(); 00286 } 00287 00288 void Billboard::removeTrajectoryPredictionMarkers() 00289 { 00290 for (int i = 1; i < PREDICTIONS_COUNT + 1; i++) 00291 { 00292 std::stringstream name; 00293 name << name_ << "_prediction_" << i; 00294 server_->erase(name.str()); 00295 } 00296 server_->applyChanges(); 00297 } 00298 00299 void Billboard::create() 00300 { 00301 clearObject(); 00302 00303 object_.header.frame_id = frame_id_; 00304 object_.name = name_; 00305 // object_.description = name_ + " billboard"; 00306 object_.pose.position.x = pose_.position.x; 00307 object_.pose.position.y = pose_.position.y; 00308 object_.pose.position.z = pose_.position.z; 00309 00310 createMesh(); 00311 00312 control_.name = "billboard_control"; 00313 control_.always_visible = true; 00314 control_.orientation_mode = InteractiveMarkerControl::VIEW_FACING; 00315 control_.interaction_mode = InteractiveMarkerControl::BUTTON; 00316 control_.markers.push_back(mesh_); 00317 object_.controls.push_back(control_); 00318 00319 createMenu(); 00320 } 00321 00322 void Billboard::insert() 00323 { 00324 create(); 00325 00326 server_->insert(object_, boost::bind(&Primitive::defaultCallback, this, _1)); 00327 menu_handler_.apply(*server_, name_); 00328 } 00329 00330 } 00331