CopAnswerDisplay.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, U. Klank
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  */
00030 
00031 #ifndef COPANSWERDISPLAY_H
00032 #define COPANSWERDISPLAY_H
00033 
00034 #include <vision_msgs/cop_answer.h>
00035 #include "jlo_display_base.h"
00036 #include "SimpleGraspPlanner.h"
00037 namespace rviz_shows_cop
00038 {
00039 
00044 class CopAnswerDisplay : public JloDisplayBase
00045 {
00046 public:
00047   CopAnswerDisplay(const std::string& name, rviz::VisualizationManager* manager);
00048 
00049   virtual ~CopAnswerDisplay();
00050 
00051   virtual void setTopic(const std::string& topic);
00052 
00053   void setSGP   (bool showGrapsPlanner);
00054   bool getSGP()
00055   {
00056     return (m_sgp);
00057   }
00058   void setHand  (bool rightHand);
00059   bool getHand()
00060   {
00061     return (m_hand);
00062   }
00063   void setSGPColor      (rviz::Color color);
00064   rviz::Color getSGPColor()
00065   {
00066     return (m_sgpColor);
00067   }
00068   void setTH    (float showGrapsPlanner);
00069   float getTH()
00070   {
00071     return (m_th);
00072   }
00073 
00074   void setOffset        (float offset);
00075   float getOffset()
00076   {
00077     return (m_offset);
00078   }
00079   void setOfftop        (float offset);
00080   float getOfftop()
00081   {
00082     return (m_offtop);
00083   }
00084 
00085   void setA     (float showGrapsPlanner);
00086   float getA()
00087   {
00088     return (alpha);
00089   }
00090   void setB     (float showGrapsPlanner);
00091   float getB()
00092   {
00093     return (beta);
00094   }
00095   void setD     (float showGrapsPlanner);
00096   float getD()
00097   {
00098     return (delta);
00099   }
00100   void setAuto  (bool rightHand);
00101   bool getAuto()
00102   {
00103     return (m_auto);
00104   }
00105 
00106 
00107   virtual void createProperties();
00108 protected:
00109   void subscribe();
00110   void unsubscribe();
00111   void incomingMessage(const vision_msgs::cop_answerConstPtr& msg);
00112   void processMessage(vision_msgs::cop_answer& msg);
00113   void processMessage(){return processMessage(m_currentMessage);};
00114 
00115   ros::Subscriber cop_subscriber;
00116 
00117   void AttachSGPPoints(Ogre::SceneNode* object, std::vector<vision_msgs::partial_lo::_pose_type > matrices,
00118                                         std::vector<vision_msgs::partial_lo::_cov_type> covs, size_t index);
00119   double GetOffsetBaseLinkRotZ(Ogre::Quaternion quat);
00120 
00121 
00122   bool m_sgp;
00123   bool m_hand;
00124   bool m_auto;
00125   float m_th;
00126   float m_offset;
00127   float m_offtop;
00128   rviz::Color m_sgpColor;
00129   HandConfig m_manConf;
00130   float alpha;
00131   float beta;
00132   float delta;
00133 
00134   rviz::BoolPropertyWPtr m_sgp_property;
00135   rviz::BoolPropertyWPtr m_hand_property;
00136   rviz::ColorPropertyWPtr m_sgpColor_prop;
00137   rviz::FloatPropertyWPtr m_th_property;
00138   rviz::FloatPropertyWPtr m_offset_property;
00139   rviz::FloatPropertyWPtr m_offtop_property;
00140   vision_msgs::cop_answer m_currentMessage;
00141 
00142   rviz::BoolPropertyWPtr  m_auto_prop;
00143   rviz::FloatPropertyWPtr m_alpha_prop;
00144   rviz::FloatPropertyWPtr m_beta_prop;
00145   rviz::FloatPropertyWPtr m_delta_prop;
00146 
00147 
00148 
00149 };
00150 
00151 } // namespace mapping_rviz_plugin
00152 
00153 #endif /* RVIZ_POLYGONAL_MAP_DISPLAY_H_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


cop_rviz_plugin
Author(s): U. Klank, Josh Faust
autogenerated on Thu May 23 2013 10:50:43