robot_state_display.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, Willow Garage, Inc.
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 /* Author: Ioan Sucan */
00031 
00032 #ifndef MOVEIT_VISUALIZATION_ROBOT_STATE_DISPLAY_RVIZ_ROBOT_STATE_DISPLAY_
00033 #define MOVEIT_VISUALIZATION_ROBOT_STATE_DISPLAY_RVIZ_ROBOT_STATE_DISPLAY_
00034 
00035 #include <rviz/display.h>
00036 
00037 #ifndef Q_MOC_RUN
00038 #include <moveit/rdf_loader/rdf_loader.h>
00039 #include <moveit/rviz_plugin_render_tools/robot_state_visualization.h>
00040 #include <moveit_msgs/DisplayRobotState.h>
00041 #include <ros/ros.h>
00042 #endif
00043 
00044 namespace Ogre
00045 {
00046 class SceneNode;
00047 }
00048 
00049 namespace rviz
00050 {
00051 class Robot;
00052 class StringProperty;
00053 class BoolProperty;
00054 class FloatProperty;
00055 class RosTopicProperty;
00056 class ColorProperty;
00057 }
00058 
00059 namespace moveit_rviz_plugin
00060 {
00061 
00062 class RobotStateVisualization;
00063 
00064 class RobotStateDisplay : public rviz::Display
00065 {
00066   Q_OBJECT
00067 
00068 public:
00069 
00070   RobotStateDisplay();
00071   virtual ~RobotStateDisplay();
00072 
00073   virtual void update(float wall_dt, float ros_dt);
00074   virtual void reset();
00075 
00076   const robot_model::RobotModelConstPtr& getRobotModel() const
00077   {
00078     return kmodel_;
00079   }
00080 
00081   void setLinkColor(const std::string &link_name, const QColor &color);
00082   void unsetLinkColor(const std::string& link_name);
00083 
00084 private Q_SLOTS:
00085 
00086   // ******************************************************************************************
00087   // Slot Event Functions
00088   // ******************************************************************************************
00089   void changedRobotDescription();
00090   void changedRootLinkName();
00091   void changedRobotSceneAlpha();
00092   void changedAttachedBodyColor();
00093   void changedRobotStateTopic();
00094   void changedEnableLinkHighlight();
00095   void changedEnableVisualVisible();
00096   void changedEnableCollisionVisible();
00097   void changedAllLinks();
00098 
00099 protected:
00100 
00101   void loadRobotModel();
00102 
00106   void calculateOffsetPosition();
00107 
00108   void setLinkColor(rviz::Robot* robot, const std::string& link_name, const QColor &color);
00109   void unsetLinkColor(rviz::Robot* robot, const std::string& link_name);
00110 
00111   void newRobotStateCallback(const moveit_msgs::DisplayRobotState::ConstPtr &state);
00112 
00113   void setRobotHighlights(const moveit_msgs::DisplayRobotState::_highlight_links_type& highlight_links);
00114   void setHighlight(const std::string& link_name, const std_msgs::ColorRGBA& color);
00115   void unsetHighlight(const std::string& link_name);
00116 
00117   // overrides from Display
00118   virtual void onInitialize();
00119   virtual void onEnable();
00120   virtual void onDisable();
00121   virtual void fixedFrameChanged();
00122 
00123   // render the robot
00124   ros::NodeHandle root_nh_;
00125   ros::Subscriber robot_state_subscriber_;
00126 
00127   RobotStateVisualizationPtr robot_;
00128   rdf_loader::RDFLoaderPtr rdf_loader_;
00129   robot_model::RobotModelConstPtr kmodel_;
00130   robot_state::RobotStatePtr kstate_;
00131   std::map<std::string, std_msgs::ColorRGBA> highlights_;
00132   bool update_state_;
00133 
00134   rviz::StringProperty* robot_description_property_;
00135   rviz::StringProperty* root_link_name_property_;
00136   rviz::RosTopicProperty* robot_state_topic_property_;
00137   rviz::FloatProperty* robot_alpha_property_;
00138   rviz::ColorProperty* attached_body_color_property_;
00139   rviz::BoolProperty* enable_link_highlight_;
00140   rviz::BoolProperty* enable_visual_visible_;
00141   rviz::BoolProperty* enable_collision_visible_;
00142   rviz::BoolProperty* show_all_links_;
00143 };
00144 
00145 } // namespace moveit_rviz_plugin
00146 
00147 #endif


visualization
Author(s): Ioan Sucan , Dave Coleman
autogenerated on Mon Oct 6 2014 02:34:03