35 #define BOOST_PARAMETER_MAX_ARITY 7
37 #include <Eigen/Geometry>
39 #include <jsk_topic_tools/color_utils.h>
54 "Amount of transparency to apply to the polygon.",
79 for (
size_t i =
clouds_.size(); i <
num; i++) {
80 Ogre::SceneNode* node =
scene_node_->createChildSceneNode();
85 node->attachObject(cloud);
92 for (
size_t i =
num; i <
clouds_.size(); i++) {
109 const jsk_recognition_msgs::SimpleOccupancyGridArray::ConstPtr& msg)
111 Ogre::ColourValue white(1, 1, 1, 1);
113 for (
size_t i = 0; i <
msg->grids.size(); i++) {
114 Ogre::SceneNode* node =
nodes_[i];
116 const jsk_recognition_msgs::SimpleOccupancyGrid grid =
msg->grids[i];
117 Ogre::Vector3 position;
118 Ogre::Quaternion quaternion;
121 geometry_msgs::Pose plane_pose;
123 Eigen::Affine3f plane_pose_eigen = plane->coordinates();
128 std::ostringstream oss;
129 oss <<
"Error transforming pose";
130 oss <<
" from frame '" << grid.header.frame_id <<
"'";
131 oss <<
" to frame '" << qPrintable(
fixed_frame_) <<
"'";
136 node->setPosition(position);
137 node->setOrientation(quaternion);
139 std::vector<rviz::PointCloud::Point> points;
140 for (
size_t ci = 0; ci < grid.cells.size(); ci++) {
141 const geometry_msgs::Point
p = grid.cells[ci];
152 points.push_back(point);
156 if (!points.empty()) {
157 cloud->
addPoints(&points.front(), points.size());