Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #pragma once
00029 #ifndef BILLBOARD_H_
00030 #define BILLBOARD_H_
00031
00032 #include "primitive.h"
00033 #include <srs_interaction_primitives/BillboardType.h>
00034 #include <OGRE/OgreVector3.h>
00035 #include <OGRE/OgreMatrix3.h>
00036 #include <OGRE/OgreQuaternion.h>
00037
00038 #define PREDICTIONS_COUNT 3
00039 #define PREDICTION_SPHERE_SIZE 0.1
00040
00041 namespace srs_interaction_primitives
00042 {
00053 class Billboard : public Primitive
00054 {
00055 public:
00062 Billboard(InteractiveMarkerServerPtr server, std::string frame_id, std::string name);
00063
00068 void setType(int type);
00069
00074 int getType();
00075
00079 void insert();
00080
00085 double getVelocity()
00086 {
00087 if (primitive_type_ != srs_interaction_primitives::PrimitiveType::BILLBOARD)
00088 ROS_WARN("This is object is not a billboard, you cannot get velocity!");
00089 return velocity_;
00090 }
00091
00096 void setDirection(geometry_msgs::Quaternion direction)
00097 {
00098 if (primitive_type_ != srs_interaction_primitives::PrimitiveType::BILLBOARD)
00099 {
00100 ROS_WARN("This is object is not a billboard, you cannot set direction!");
00101 return;
00102 }
00103
00104 geometry_msgs::Quaternion direction_change;
00105 direction_change.x = direction.w - direction_.x;
00106 direction_change.y = direction.y - direction_.y;
00107 direction_change.z = direction.z - direction_.z;
00108 direction_change.w = direction.w - direction_.w;
00109
00110 updatePublisher_->publishMovementChanged(direction, direction_change, velocity_, 0.0f);
00111
00112 direction_ = direction;
00113 }
00114
00119 geometry_msgs::Quaternion getDirection()
00120 {
00121 if (primitive_type_ != srs_interaction_primitives::PrimitiveType::BILLBOARD)
00122 ROS_WARN("This is object is not a billboard, you cannot get direction!");
00123 return direction_;
00124 }
00125
00130 void setVelocity(double velocity)
00131 {
00132 if (primitive_type_ != srs_interaction_primitives::PrimitiveType::BILLBOARD)
00133 {
00134 ROS_WARN("This is object is not a billboard, you cannot set velocity!");
00135 return;
00136 }
00137 updatePublisher_->publishMovementChanged(direction_, geometry_msgs::Quaternion(), velocity, velocity - velocity_);
00138 velocity_ = velocity;
00139 }
00140
00144 void addTrajectoryControls();
00145
00149 void removeTrajectoryControls();
00150
00154 void updateControls();
00155
00159 void menuCallback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &);
00160
00161 private:
00162
00163 double velocity_;
00164 geometry_msgs::Quaternion direction_;
00165 int billboard_type_;
00166 visualization_msgs::Marker mesh_;
00167
00168 void create();
00169 void createMenu();
00170 void createMesh();
00171 void addTrajectoryPredictionMarkers();
00172 void removeTrajectoryPredictionMarkers();
00173 };
00174 }
00175 #endif