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