41 #include <QApplication>
47 : robot_(root_node, context,
name, parent_property)
51 , visual_visible_(true)
52 , collision_visible_(false)
54 default_attached_object_color_.r = 0.0f;
55 default_attached_object_color_.g = 0.7f;
56 default_attached_object_color_.b = 0.0f;
57 default_attached_object_color_.a = 1.0f;
58 render_shapes_ = std::make_shared<RenderShapes>(context);
85 render_shapes_->updateShapeColors(attached_object_color.r, attached_object_color.g, attached_object_color.b,
95 const std_msgs::ColorRGBA& default_attached_object_color)
97 updateHelper(kinematic_state, default_attached_object_color,
nullptr);
101 const std_msgs::ColorRGBA& default_attached_object_color,
102 const std::map<std::string, std_msgs::ColorRGBA>& color_map)
104 updateHelper(kinematic_state, default_attached_object_color, &color_map);
108 const std_msgs::ColorRGBA& default_attached_object_color,
109 const std::map<std::string, std_msgs::ColorRGBA>* color_map)
114 std::vector<const moveit::core::AttachedBody*> attached_bodies;
115 kinematic_state->getAttachedBodies(attached_bodies);
118 std_msgs::ColorRGBA color = default_attached_object_color;
122 std::map<std::string, std_msgs::ColorRGBA>::const_iterator it = color_map->find(attached_body->getName());
123 if (it != color_map->end())
132 ROS_ERROR_STREAM(
"Link " << attached_body->getAttachedLinkName() <<
" not found in rviz::Robot");
137 const std::vector<shapes::ShapeConstPtr>& ab_shapes = attached_body->getShapes();
138 for (std::size_t j = 0; j < ab_shapes.size(); ++j)