32 #include <OgreSceneManager.h>
33 #include <OgreSceneNode.h>
34 #include <OgreWireBoundingBox.h>
69 return ((uint)iam.
index) + ((uint)(iam.
message >> 32)) + ((uint)(iam.
message & 0xffffffff));
87 QHash<IndexAndMessage, Property*>::const_iterator iter;
121 Ogre::Vector3
pointFromCloud(
const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t index)
127 const uint32_t xoff = cloud->fields[xi].offset;
128 const uint32_t yoff = cloud->fields[yi].offset;
129 const uint32_t zoff = cloud->fields[zi].offset;
130 const uint8_t type = cloud->fields[xi].datatype;
131 const uint32_t point_step = cloud->point_step;
132 float x = valueFromCloud<float>(cloud, xoff, type, point_step, index);
133 float y = valueFromCloud<float>(cloud, yoff, type, point_step, index);
134 float z = valueFromCloud<float>(cloud, zoff, type, point_step, index);
135 return Ogre::Vector3(x, y, z);
140 typedef std::set<int> S_int;
145 for (; it != end; ++it)
147 uint64_t handle = *it;
148 indices.insert((handle & 0xffffffff) - 1);
153 S_int::iterator it = indices.begin();
154 S_int::iterator end = indices.end();
155 for (; it != end; ++it)
164 new Property(QString(
"Point %1 [cloud 0x%2]").arg(index).arg((uint64_t)message.get()),
165 QVariant(),
"", parent_property);
174 for (
size_t field = 0; field < message->fields.size(); ++field)
176 const sensor_msgs::PointField&
f = message->fields[field];
177 const std::string& name =
f.name;
179 if (name ==
"x" || name ==
"y" || name ==
"z" || name ==
"X" || name ==
"Y" || name ==
"Z")
183 if (name ==
"rgb" || name ==
"rgba")
186 valueFromCloud<float>(message,
f.offset,
f.datatype, message->point_step, index);
189 uint32_t val = *((uint32_t*)&float_val);
191 new ColorProperty(QString(
"%1: %2").arg(field).arg(QString::fromStdString(name)),
192 QColor((val >> 16) & 0xff, (val >> 8) & 0xff, val & 0xff),
"", cat);
200 float val = valueFromCloud<float>(message,
f.offset,
f.datatype, message->point_step, index);
202 QString(
"%1: %2").arg(field).arg(QString::fromStdString(name)), val,
"", cat);
213 typedef std::set<int> S_int;
218 for (; it != end; ++it)
220 uint64_t handle = *it;
221 indices.insert((handle & 0xffffffff) - 1);
226 S_int::iterator it = indices.begin();
227 S_int::iterator end = indices.end();
228 for (; it != end; ++it)
245 for (; it != end; ++it)
247 M_HandleToBox::iterator find_it =
boxes_.find(std::make_pair(obj.
handle, *it - 1));
248 if (find_it !=
boxes_.end())
250 Ogre::WireBoundingBox* box = find_it->second.second;
252 aabbs.push_back(box->getWorldBoundingBox());
261 for (; it != end; ++it)
263 int index = (*it & 0xffffffff) - 1;
272 Ogre::AxisAlignedBox aabb(pos - size, pos + size);
282 for (; it != end; ++it)
284 int global_index = (*it & 0xffffffff) - 1;
318 "Whether or not the points in this point cloud are selectable.",
display_,
322 "Rendering mode to use, in order of computational complexity.",
339 "Amount of transparency to apply to the points. "
340 "Note that this is experimental and does not always look correct.",
347 "Duration, in seconds, to keep the incoming points. 0 means only show the latest points.",
353 "Set the transformer to use to set the position of the points.",
display_,
360 "Set the transformer to use to set the color of the points.",
display_,
392 std::vector<std::string>::iterator ci;
394 for (ci = classes.begin(); ci != classes.end(); ci++)
396 const std::string& lookup_name = *ci;
401 ROS_ERROR(
"Transformer type [%s] is already loaded.", name.c_str());
463 cloud_infos_[i]->cloud_->setPickColor(Ogre::ColourValue(0.0
f, 0.0
f, 0.0
f, 0.0
f));
502 cloud_infos_[i]->cloud_->setDimensions(size, size, size);
544 now_sec -
cloud_infos_.front()->receive_time_.toSec() >= point_decay_time)
557 for (; it != end; ++it)
559 if (!(*it)->selection_handler_.get() || !(*it)->selection_handler_->hasSelections())
581 for (; it != end; ++it)
585 V_CloudInfo::iterator next = it;
588 if (next != end && now_sec - cloud_info->receive_time_.toSec() >= point_decay_time)
593 bool per_point_alpha =
findChannelIndex(cloud_info->message_,
"rgba") != -1;
596 cloud_info->cloud_->setRenderMode(mode);
597 cloud_info->cloud_->addPoints(&(cloud_info->transformed_points_.front()),
598 cloud_info->transformed_points_.size());
600 cloud_info->cloud_->setDimensions(size, size, size);
605 cloud_info->scene_node_ =
606 scene_node_->createChildSceneNode(cloud_info->position_, cloud_info->orientation_);
608 cloud_info->scene_node_->attachObject(cloud_info->cloud_.get());
610 cloud_info->selection_handler_.reset(
623 if (lock.owns_lock())
629 for (; it != end; ++it)
631 const std::string& name = it->first;
649 for (
int i = 0; i < props.size(); i++)
651 props[i]->setHidden(hide);
664 typedef std::set<std::pair<uint8_t, std::string> >
S_string;
666 bool cur_xyz_valid =
false;
667 bool cur_color_valid =
false;
668 bool has_rgb_transformer =
false;
669 M_TransformerInfo::iterator trans_it =
transformers_.begin();
671 for (; trans_it != trans_end; ++trans_it)
673 const std::string& name = trans_it->first;
675 uint32_t mask = trans->supports(cloud);
678 valid_xyz.insert(std::make_pair(trans->score(cloud), name));
679 if (name == xyz_name)
681 cur_xyz_valid =
true;
688 valid_color.insert(std::make_pair(trans->score(cloud), name));
689 if (name == color_name)
691 cur_color_valid =
true;
695 has_rgb_transformer =
true;
703 if (!valid_xyz.empty())
709 if (!cur_color_valid)
711 if (!valid_color.empty())
713 if (has_rgb_transformer)
727 std::stringstream ss;
735 info->message_ = cloud;
809 for (; it != end; ++it)
813 cloud_info->cloud_->clear();
814 cloud_info->cloud_->addPoints(&cloud_info->transformed_points_.front(),
815 cloud_info->transformed_points_.size());
821 if (!cloud_info->scene_node_)
824 cloud_info->orientation_))
826 std::stringstream ss;
827 ss <<
"Failed to transform from frame [" << cloud_info->message_->header.frame_id <<
"] to frame ["
834 Ogre::Matrix4 transform;
835 transform.makeTransform(cloud_info->position_, Ogre::Vector3(1, 1, 1), cloud_info->orientation_);
838 cloud_points.clear();
840 size_t size = cloud_info->message_->width * cloud_info->message_->height;
842 default_pt.
color = Ogre::ColourValue(1, 1, 1);
843 default_pt.
position = Ogre::Vector3::ZERO;
844 cloud_points.resize(size, default_pt);
848 if (update_transformers)
857 std::stringstream ss;
858 ss <<
"No position transformer available for cloud";
865 std::stringstream ss;
866 ss <<
"No color transformer available for cloud";
877 for (V_PointCloudPoint::iterator cloud_point = cloud_points.begin(); cloud_point != cloud_points.end();
882 cloud_point->position.x = 999999.0f;
883 cloud_point->position.y = 999999.0f;
884 cloud_point->position.z = 999999.0f;
892 sensor_msgs::PointCloud2& output)
894 output.header = input.header;
895 output.width = input.points.size();
897 output.fields.resize(3 + input.channels.size());
899 output.fields[0].name =
"x";
900 output.fields[1].name =
"y";
901 output.fields[2].name =
"z";
904 for (
size_t d = 0;
d < output.fields.size(); ++
d, offset += 4)
906 output.fields[
d].offset = offset;
907 output.fields[
d].datatype = sensor_msgs::PointField::FLOAT32;
909 output.point_step = offset;
910 output.row_step = output.point_step * output.width;
912 for (
size_t d = 0;
d < input.channels.size(); ++
d)
913 output.fields[3 +
d].name = input.channels[
d].name;
914 output.data.resize(input.points.size() * output.point_step);
915 output.is_bigendian =
false;
916 output.is_dense =
false;
919 for (
size_t cp = 0; cp < input.points.size(); ++cp)
921 memcpy(&output.data[cp * output.point_step + output.fields[0].offset], &input.points[cp].x,
923 memcpy(&output.data[cp * output.point_step + output.fields[1].offset], &input.points[cp].y,
925 memcpy(&output.data[cp * output.point_step + output.fields[2].offset], &input.points[cp].z,
927 for (
size_t d = 0;
d < input.channels.size(); ++
d)
929 if (input.channels[
d].values.size() == input.points.size())
931 memcpy(&output.data[cp * output.point_step + output.fields[3 +
d].offset],
932 &input.channels[
d].values[cp],
sizeof(
float));
941 sensor_msgs::PointCloud2Ptr out(
new sensor_msgs::PointCloud2);
977 const sensor_msgs::PointCloud2ConstPtr& msg =
cloud_infos_.front()->message_;
981 for (; it != end; ++it)
984 if ((trans->supports(msg) & mask) == mask)
986 prop->
addOption(QString::fromStdString(it->first));