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
00029
00030
00031
00032 #ifndef MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_ROBOT_STATE_VISUALIZATION_
00033 #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_ROBOT_STATE_VISUALIZATION_
00034
00035 #include <moveit/robot_state/robot_state.h>
00036 #include <moveit/rviz_plugin_render_tools/octomap_render.h>
00037 #include <rviz/robot/robot.h>
00038
00039 namespace moveit_rviz_plugin
00040 {
00041
00042 class RenderShapes;
00043 typedef boost::shared_ptr<RenderShapes> RenderShapesPtr;
00044
00046 class RobotStateVisualization
00047 {
00048 public:
00049
00050 RobotStateVisualization(Ogre::SceneNode* root_node, rviz::DisplayContext* context,
00051 const std::string& name, rviz::Property* parent_property);
00052
00053 rviz::Robot& getRobot()
00054 {
00055 return robot_;
00056 }
00057
00058 void load(const urdf::ModelInterface &descr, bool visual = true, bool collision = true);
00059 void clear();
00060
00061 void update(const robot_state::RobotStateConstPtr &kinematic_state);
00062 void update(const robot_state::RobotStateConstPtr &kinematic_state, const std_msgs::ColorRGBA &default_attached_object_color);
00063 void update(const robot_state::RobotStateConstPtr &kinematic_state, const std_msgs::ColorRGBA &default_attached_object_color,
00064 const std::map<std::string, std_msgs::ColorRGBA> &color_map);
00065 void setDefaultAttachedObjectColor(const std_msgs::ColorRGBA &default_attached_object_color);
00066
00071 void setVisible(bool visible);
00072
00077 void setVisualVisible(bool visible);
00078
00083 void setCollisionVisible(bool visible);
00084
00085 void setAlpha(float alpha);
00086
00087 private:
00088
00089 void updateHelper(const robot_state::RobotStateConstPtr &kinematic_state,
00090 const std_msgs::ColorRGBA &default_attached_object_color,
00091 const std::map<std::string, std_msgs::ColorRGBA> *color_map);
00092 rviz::Robot robot_;
00093 RenderShapesPtr render_shapes_;
00094 std_msgs::ColorRGBA default_attached_object_color_;
00095 OctreeVoxelRenderMode octree_voxel_render_mode_;
00096 OctreeVoxelColorMode octree_voxel_color_mode_;
00097
00098 bool visible_;
00099 bool visual_visible_;
00100 bool collision_visible_;
00101
00102 };
00103
00104 typedef boost::shared_ptr<RobotStateVisualization> RobotStateVisualizationPtr;
00105 typedef boost::shared_ptr<const RobotStateVisualization> RobotStateVisualizationConstPtr;
00106
00107 }
00108
00109 #endif