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 #include <moveit/rviz_plugin_render_tools/planning_scene_render.h>
00033 #include <moveit/rviz_plugin_render_tools/robot_state_visualization.h>
00034 #include <moveit/rviz_plugin_render_tools/render_shapes.h>
00035 #include <rviz/display_context.h>
00036
00037 #include <OGRE/OgreSceneNode.h>
00038 #include <OGRE/OgreSceneManager.h>
00039
00040 namespace moveit_rviz_plugin
00041 {
00042
00043 PlanningSceneRender::PlanningSceneRender(Ogre::SceneNode *node, rviz::DisplayContext *context, const RobotStateVisualizationPtr &robot) :
00044 planning_scene_geometry_node_(node->createChildSceneNode()),
00045 context_(context),
00046 scene_robot_(robot)
00047 {
00048 render_shapes_.reset(new RenderShapes(context));
00049 }
00050
00051 PlanningSceneRender::~PlanningSceneRender()
00052 {
00053 context_->getSceneManager()->destroySceneNode(planning_scene_geometry_node_->getName());
00054 }
00055
00056 void PlanningSceneRender::clear()
00057 {
00058 render_shapes_->clear();
00059 }
00060
00061 void PlanningSceneRender::renderPlanningScene(const planning_scene::PlanningSceneConstPtr &scene,
00062 const rviz::Color &default_env_color,
00063 const rviz::Color &default_attached_color,
00064 OctreeVoxelRenderMode octree_voxel_rendering,
00065 OctreeVoxelColorMode octree_color_mode,
00066 float default_scene_alpha)
00067 {
00068 if (!scene)
00069 return;
00070
00071 clear();
00072
00073 if (scene_robot_)
00074 {
00075 robot_state::RobotStateConstPtr ks(new robot_state::RobotState(scene->getCurrentState()));
00076 std_msgs::ColorRGBA color;
00077 color.r = default_attached_color.r_;
00078 color.g = default_attached_color.g_;
00079 color.b = default_attached_color.b_;
00080 color.a = 1.0f;
00081 planning_scene::ObjectColorMap color_map;
00082 scene->getKnownObjectColors(color_map);
00083 scene_robot_->update(ks, color, color_map);
00084 }
00085
00086 const std::vector<std::string> &ids = scene->getWorld()->getObjectIds();
00087 for (std::size_t i = 0 ; i < ids.size() ; ++i)
00088 {
00089 collision_detection::CollisionWorld::ObjectConstPtr o = scene->getWorld()->getObject(ids[i]);
00090 rviz::Color color = default_env_color;
00091 float alpha = default_scene_alpha;
00092 if (scene->hasObjectColor(ids[i]))
00093 {
00094 const std_msgs::ColorRGBA &c = scene->getObjectColor(ids[i]);
00095 color.r_ = c.r; color.g_ = c.g; color.b_ = c.b;
00096 alpha = c.a;
00097 }
00098 for (std::size_t j = 0 ; j < o->shapes_.size() ; ++j)
00099 render_shapes_->renderShape(planning_scene_geometry_node_, o->shapes_[j].get(), o->shape_poses_[j],
00100 octree_voxel_rendering, octree_color_mode, color, alpha);
00101 }
00102 }
00103
00104 }