$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id: Primitive.h 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: 24/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 #pragma once 00029 #ifndef PRIMITIVE_H_ 00030 #define PRIMITIVE_H_ 00031 00032 #include <ros/ros.h> 00033 #include <interactive_markers/interactive_marker_server.h> 00034 #include <interactive_markers/tools.h> 00035 #include <interactive_markers/menu_handler.h> 00036 #include <geometry_msgs/Point.h> 00037 #include <geometry_msgs/Polygon.h> 00038 #include <std_msgs/ColorRGBA.h> 00039 #include <OGRE/OgreVector3.h> 00040 #include <arm_navigation_msgs/Shape.h> 00041 00042 #include <tf/tf.h> 00043 #include <tf/transform_listener.h> 00044 00045 #include <srs_interaction_primitives/parameters_list.h> 00046 #include <srs_interaction_primitives/PrimitiveType.h> 00047 #include <srs_interaction_primitives/PoseType.h> 00048 #include "update_publisher.h" 00049 00050 #define MEASURE_TEXT_SCALE 0.2 00051 #define MEASURE_TEXT_MAX_SIZE 0.3 00052 #define MEASURE_TEXT_MIN_SIZE 0.1 00053 00054 #define GRASP_ARROW_LENGTH 0.25 00055 #define GRASP_ARROW_WIDTH 0.2 00056 #define GRASP_TEXT_OFFSET 0.1 00057 #define GRASP_TEXT_SIZE 0.1 00058 #define GRASP_POINT_SCALE 0.05 00059 #define GRASP_TRANSPARENCY 0.3 00060 00061 namespace srs_interaction_primitives 00062 { 00063 00064 typedef boost::shared_ptr<interactive_markers::InteractiveMarkerServer> InteractiveMarkerServerPtr; 00065 typedef geometry_msgs::Vector3 Scale; 00066 00071 float maxScale(geometry_msgs::Vector3 scale); 00072 00077 float minScale(geometry_msgs::Vector3 scale); 00078 00084 class Primitive 00085 { 00086 public: 00093 Primitive(InteractiveMarkerServerPtr server, std::string frame_id, std::string name, int type); 00094 00098 Primitive() 00099 { 00100 } 00101 00105 virtual ~Primitive() 00106 { 00107 this->erase(); 00108 server_->applyChanges(); 00109 } 00110 00114 virtual void insert(); 00115 00119 virtual void erase(); 00120 00125 void changeColor(std_msgs::ColorRGBA color); 00126 00131 void setPoseType(int type) 00132 { 00133 if (type == PoseType::POSE_CENTER || type == PoseType::POSE_BASE) 00134 { 00135 pose_type_ = type; 00136 } 00137 } 00138 00143 int getPoseType() 00144 { 00145 return pose_type_; 00146 } 00147 00152 void setPrimitiveType(int type) 00153 { 00154 primitive_type_ = type; 00155 delete updatePublisher_; 00156 updatePublisher_ = new UpdatePublisher(name_, primitive_type_); 00157 } 00158 00163 int getPrimitiveType() 00164 { 00165 return primitive_type_; 00166 } 00167 00172 std::string getUpdateTopic(int update_type) 00173 { 00174 return updatePublisher_->getUpdateTopic(update_type); 00175 } 00176 00181 std::string getName() 00182 { 00183 return name_; 00184 } 00185 00190 void setColor(std_msgs::ColorRGBA color) 00191 { 00192 color_ = color; 00193 } 00194 00199 std_msgs::ColorRGBA getColor() 00200 { 00201 return color_; 00202 } 00203 00208 void setPose(geometry_msgs::Pose pose) 00209 { 00210 if (pose_type_ == PoseType::POSE_BASE) 00211 { 00212 pose.position.z += scale_.z * 0.5; 00213 } 00214 00215 geometry_msgs::Pose pose_change; 00216 pose_change.position.x = pose.position.x - pose_.position.x; 00217 pose_change.position.y = pose.position.y - pose_.position.y; 00218 pose_change.position.z = pose.position.z - pose_.position.z; 00219 pose_change.orientation.x = pose.orientation.x - pose_.orientation.x; 00220 pose_change.orientation.y = pose.orientation.y - pose_.orientation.y; 00221 pose_change.orientation.z = pose.orientation.z - pose_.orientation.z; 00222 pose_change.orientation.w = pose.orientation.w - pose_.orientation.w; 00223 pose_ = pose; 00224 object_.pose = pose_; 00225 updatePublisher_->publishPoseChanged(pose_, pose_change); 00226 } 00227 00232 geometry_msgs::Pose getPose() 00233 { 00234 return pose_; 00235 } 00236 00241 void setScale(geometry_msgs::Vector3 scale) 00242 { 00243 if (pose_type_ == PoseType::POSE_BASE) 00244 { 00245 pose_.position.z -= scale_.z * 0.5; 00246 pose_.position.z += scale.z * 0.5; 00247 } 00248 00249 geometry_msgs::Vector3 scale_change; 00250 scale_change.x = scale.x - scale_.x; 00251 scale_change.y = scale.y - scale_.y; 00252 scale_change.z = scale.z - scale_.z; 00253 scale_ = scale; 00254 object_.scale = srs_interaction_primitives::maxScale(scale_); 00255 updatePublisher_->publishScaleChanged(scale_, scale_change); 00256 } 00257 00262 geometry_msgs::Vector3 getScale() 00263 { 00264 return scale_; 00265 } 00266 00271 void setDescription(std::string description) 00272 { 00273 description_ = description; 00274 } 00275 00280 std::string getDescription() 00281 { 00282 return description_; 00283 } 00284 00289 void setFrameID(std::string frame_id) 00290 { 00291 frame_id_ = frame_id; 00292 } 00293 00298 std::string getFrameID() 00299 { 00300 return frame_id_; 00301 } 00302 00306 void updateControls(); 00307 00312 visualization_msgs::InteractiveMarkerControl * getControl(std::string name); 00313 00317 virtual void defaultCallback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback); 00318 00319 protected: 00323 virtual void create() 00324 { 00325 } 00326 00330 virtual void createMenu() 00331 { 00332 } 00333 00337 void addDescriptionControl(); 00338 00342 void addMeasureControl(); 00343 00348 void addMovementControls(); 00349 00353 void addRotationControls(); 00354 00358 void removeMovementControls(); 00359 00363 void removeRotationControls(); 00364 00368 void removeMeasureControl(); 00369 00373 void removeDescriptionControl(); 00374 00379 void removeControl(std::string name); 00380 00384 void clearObject(); 00385 00389 void addScaleControls(); 00390 00394 virtual void updateScaleControls(); 00395 00399 void removeScaleControls(); 00400 00404 void scaleFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback); 00405 00406 geometry_msgs::Vector3 min_size_, max_size_; 00407 int primitive_type_; 00408 visualization_msgs::InteractiveMarker object_; 00409 visualization_msgs::InteractiveMarkerControl control_, descriptionControl_, measureControl_, scaleControl_, 00410 trajectoryControl_; 00411 visualization_msgs::InteractiveMarkerControl moveXControl_, moveYControl_, moveZControl_, rotateXControl_, 00412 rotateYControl, rotateZControl_; 00413 interactive_markers::MenuHandler menu_handler_; 00414 00415 // Transform listener 00416 tf::TransformListener *tfListener; 00417 00418 // Transformer 00419 tf::Transformer transformer; 00420 00421 // Transformations 00422 tf::StampedTransform feedbackToDefaultTransform; 00423 00424 // Common attributes 00425 std::string name_, description_, frame_id_; 00426 InteractiveMarkerServerPtr server_; 00427 geometry_msgs::Pose pose_; 00428 geometry_msgs::Vector3 scale_; 00429 std_msgs::ColorRGBA color_, color_green_a01_; 00430 int pose_type_; 00431 geometry_msgs::Pose pose_change; 00432 00433 UpdatePublisher *updatePublisher_; 00434 00435 bool show_movement_control_, show_scale_control_, show_rotation_control_, show_measure_control_, 00436 show_description_control_, show_trajectory_control_; 00437 bool menu_created_; 00438 00439 geometry_msgs::Vector3 scale_prev_; 00440 int scale_saved_; 00441 }; 00442 00443 00444 } 00445 #endif /* PRIMITIVE_H_ */