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
00033
00034
00035
00036
00037 #include <moveit/rviz_plugin_render_tools/robot_state_visualization.h>
00038 #include <moveit/rviz_plugin_render_tools/planning_link_updater.h>
00039 #include <moveit/rviz_plugin_render_tools/render_shapes.h>
00040
00041 namespace moveit_rviz_plugin
00042 {
00043 RobotStateVisualization::RobotStateVisualization(Ogre::SceneNode* root_node, rviz::DisplayContext* context,
00044 const std::string& name, rviz::Property* parent_property)
00045 : robot_(root_node, context, name, parent_property)
00046 , octree_voxel_render_mode_(OCTOMAP_OCCUPIED_VOXELS)
00047 , octree_voxel_color_mode_(OCTOMAP_Z_AXIS_COLOR)
00048 , visible_(true)
00049 , visual_visible_(true)
00050 , collision_visible_(false)
00051 {
00052 default_attached_object_color_.r = 0.0f;
00053 default_attached_object_color_.g = 0.7f;
00054 default_attached_object_color_.b = 0.0f;
00055 default_attached_object_color_.a = 1.0f;
00056 render_shapes_.reset(new RenderShapes(context));
00057 }
00058
00059 void RobotStateVisualization::load(const urdf::ModelInterface& descr, bool visual, bool collision)
00060 {
00061
00062 clear();
00063
00064 robot_.load(descr, visual, collision);
00065 robot_.setVisualVisible(visual_visible_);
00066 robot_.setCollisionVisible(collision_visible_);
00067 robot_.setVisible(visible_);
00068 }
00069
00070 void RobotStateVisualization::clear()
00071 {
00072 render_shapes_->clear();
00073 robot_.clear();
00074 }
00075
00076 void RobotStateVisualization::setDefaultAttachedObjectColor(const std_msgs::ColorRGBA& default_attached_object_color)
00077 {
00078 default_attached_object_color_ = default_attached_object_color;
00079 }
00080
00081 void RobotStateVisualization::update(const robot_state::RobotStateConstPtr& kinematic_state)
00082 {
00083 updateHelper(kinematic_state, default_attached_object_color_, NULL);
00084 }
00085
00086 void RobotStateVisualization::update(const robot_state::RobotStateConstPtr& kinematic_state,
00087 const std_msgs::ColorRGBA& default_attached_object_color)
00088 {
00089 updateHelper(kinematic_state, default_attached_object_color, NULL);
00090 }
00091
00092 void RobotStateVisualization::update(const robot_state::RobotStateConstPtr& kinematic_state,
00093 const std_msgs::ColorRGBA& default_attached_object_color,
00094 const std::map<std::string, std_msgs::ColorRGBA>& color_map)
00095 {
00096 updateHelper(kinematic_state, default_attached_object_color, &color_map);
00097 }
00098
00099 void RobotStateVisualization::updateHelper(const robot_state::RobotStateConstPtr& kinematic_state,
00100 const std_msgs::ColorRGBA& default_attached_object_color,
00101 const std::map<std::string, std_msgs::ColorRGBA>* color_map)
00102 {
00103 robot_.update(PlanningLinkUpdater(kinematic_state));
00104 render_shapes_->clear();
00105
00106 std::vector<const robot_state::AttachedBody*> attached_bodies;
00107 kinematic_state->getAttachedBodies(attached_bodies);
00108 for (std::size_t i = 0; i < attached_bodies.size(); ++i)
00109 {
00110 std_msgs::ColorRGBA color = default_attached_object_color;
00111 float alpha = robot_.getAlpha();
00112 if (color_map)
00113 {
00114 std::map<std::string, std_msgs::ColorRGBA>::const_iterator it = color_map->find(attached_bodies[i]->getName());
00115 if (it != color_map->end())
00116 {
00117 color.r = std::max(1.0f, it->second.r * 1.05f);
00118 color.g = std::max(1.0f, it->second.g * 1.05f);
00119 color.b = std::max(1.0f, it->second.b * 1.05f);
00120 alpha = color.a = it->second.a;
00121 }
00122 }
00123 rviz::Color rcolor(color.r, color.g, color.b);
00124 const EigenSTL::vector_Affine3d& ab_t = attached_bodies[i]->getGlobalCollisionBodyTransforms();
00125 const std::vector<shapes::ShapeConstPtr>& ab_shapes = attached_bodies[i]->getShapes();
00126 for (std::size_t j = 0; j < ab_shapes.size(); ++j)
00127 {
00128 render_shapes_->renderShape(robot_.getVisualNode(), ab_shapes[j].get(), ab_t[j], octree_voxel_render_mode_,
00129 octree_voxel_color_mode_, rcolor, alpha);
00130 render_shapes_->renderShape(robot_.getCollisionNode(), ab_shapes[j].get(), ab_t[j], octree_voxel_render_mode_,
00131 octree_voxel_color_mode_, rcolor, alpha);
00132 }
00133 }
00134 robot_.setVisualVisible(visual_visible_);
00135 robot_.setCollisionVisible(collision_visible_);
00136 robot_.setVisible(visible_);
00137 }
00138
00139 void RobotStateVisualization::setVisible(bool visible)
00140 {
00141 visible_ = visible;
00142 robot_.setVisible(visible);
00143 }
00144
00145 void RobotStateVisualization::setVisualVisible(bool visible)
00146 {
00147 visual_visible_ = visible;
00148 robot_.setVisualVisible(visible);
00149 }
00150
00151 void RobotStateVisualization::setCollisionVisible(bool visible)
00152 {
00153 collision_visible_ = visible;
00154 robot_.setCollisionVisible(visible);
00155 }
00156
00157 void RobotStateVisualization::setAlpha(float alpha)
00158 {
00159 robot_.setAlpha(alpha);
00160 }
00161 }