Go to the documentation of this file.
30 #include <QRegularExpression>
45 #include <boost/bind/bind.hpp>
46 #include <boost/algorithm/string/erase.hpp>
47 #include <boost/foreach.hpp>
48 #include <boost/shared_ptr.hpp>
50 #include <OgreSceneNode.h>
51 #include <OgreSceneManager.h>
71 , messages_received_(0)
77 , angular_thres_(0.5
f)
82 QRegularExpression depth_filter(
"depth", QRegularExpression::CaseInsensitiveOption);
86 "List only topics with names that relate to depth and color images",
this,
90 "Depth Map Topic",
"", QString::fromStdString(ros::message_traits::datatype<sensor_msgs::Image>()),
94 new EnumProperty(
"Depth Map Transport Hint",
"raw",
"Preferred method of sending images.",
this,
103 QRegularExpression color_filter(
"color|rgb|bgr|gray|mono", QRegularExpression::CaseInsensitiveOption);
106 "Color Image Topic",
"",
107 QString::fromStdString(ros::message_traits::datatype<sensor_msgs::Image>()),
111 new EnumProperty(
"Color Transport Hint",
"raw",
"Preferred method of sending images.",
this,
123 "Advanced: set the size of the incoming message queue. Increasing this "
124 "is useful if your incoming TF data is delayed significantly from your"
125 " image data, but it can greatly increase memory usage if the messages are big.",
131 "Automatically scale each point based on its depth value and the camera parameters.",
this,
135 new FloatProperty(
"Auto Size Factor", 1,
"Scaling factor to be applied to the auto size.",
141 "Keep points alive after they have been occluded by a closer point. Points are "
142 "removed after a timeout or when the camera frame moves.",
147 "Amount of seconds before removing occluded points from the depth cloud",
187 if (
datatype == ros::message_traits::datatype<sensor_msgs::Image>())
194 int index = topic.lastIndexOf(
"/");
197 ROS_WARN(
"DepthCloudDisplay::setTopic() Invalid topic name: %s", topic.toStdString().c_str());
200 QString transport = topic.mid(index + 1);
201 QString base_topic = topic.mid(0, index);
239 if (use_occlusion_compensation)
293 if (!depthmap_topic.empty() && !depthmap_transport.empty())
309 if (!color_topic.empty() && !color_transport.empty())
393 const sensor_msgs::ImageConstPtr& rgb_msg)
400 std::ostringstream
s;
407 sensor_msgs::CameraInfo::ConstPtr cam_info;
413 if (!cam_info || !depth_msg)
419 s << depth_msg->width <<
" x " << depth_msg->height;
425 s << rgb_msg->width <<
" x " << rgb_msg->height;
428 if (depth_msg->header.frame_id != rgb_msg->header.frame_id)
430 std::stringstream errorMsg;
431 errorMsg <<
"Depth image frame id [" << depth_msg->header.frame_id.c_str()
432 <<
"] doesn't match color image frame id [" << rgb_msg->header.frame_id.c_str() <<
"]";
439 float f = cam_info->K[0];
440 float bx = cam_info->binning_x > 0 ? cam_info->binning_x : 1.0;
447 if (use_occlusion_compensation)
450 Ogre::Quaternion orientation;
451 Ogre::Vector3 position;
456 QString(
"Failed to transform from frame [") + depth_msg->header.frame_id.c_str() +
468 float angle_deg =
angle.valueDegrees();
469 if (angle_deg >= 180.0
f)
471 if (angle_deg < -180.0
f)
489 sensor_msgs::PointCloud2Ptr cloud_msg =
492 if (!cloud_msg.get())
496 cloud_msg->header = depth_msg->header;
511 "image_transport",
"image_transport::SubscriberPlugin");
520 std::string transport_name = boost::erase_last_copy(lookup_name,
"_sub");
521 transport_name = transport_name.substr(lookup_name.find(
'/') + 1);
550 property->clearOptions();
552 std::vector<std::string> choices;
554 choices.push_back(
"raw");
559 ros::master::V_TopicInfo::iterator it = topics.begin();
560 ros::master::V_TopicInfo::iterator end = topics.end();
561 for (; it != end; ++it)
569 const std::string& topic_name = ti.
name;
572 if (topic_name.find(topic) == 0 && topic_name != topic && topic_name[topic.size()] ==
'/' &&
573 topic_name.find(
'/', topic.size() + 1) == std::string::npos)
575 std::string transport_type = topic_name.substr(topic.size() + 1);
581 choices.push_back(transport_type);
586 for (
size_t i = 0; i < choices.size(); i++)
588 property->addOptionStd(choices[i]);
boost::shared_ptr< image_transport::SubscriberFilter > rgb_sub_
virtual bool getBool() const
PointCloudCommon * pointcloud_common_
bool isEnabled() const
Return true if this Display is enabled, false if not.
IMAGE_TRANSPORT_DECL std::string getCameraInfoTopic(const std::string &base_topic)
void setAutoSize(bool auto_size)
sensor_msgs::PointCloud2Ptr generatePointCloudFromDepth(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &color_msg, sensor_msgs::CameraInfoConstPtr camera_info_msg)
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
virtual void setHidden(bool hidden)
Hide or show this property in any PropertyTreeWidget viewing its parent.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
EnumProperty * xyz_transformer_property_
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
bool initialized() const
Returns true if the display has been initialized.
virtual void setString(const QString &str)
Set the value of this property to the given string. Does not force the value to be one of the list of...
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
virtual void updateUseOcclusionCompensation()
void update(float wall_dt, float ros_dt)
ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicyDepthColor
Property * topic_filter_property_
virtual void setString(const QString &str)
boost::scoped_ptr< image_transport::ImageTransport > depthmap_it_
IntProperty * queue_size_property_
void requestOptions(EnumProperty *property_in_need_of_options)
requestOptions() is emitted each time createEditor() is called.
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
boost::shared_ptr< SynchronizerDepthColor > sync_depth_color_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
boost::scoped_ptr< image_transport::ImageTransport > rgb_it_
const char * what() const override
virtual QVariant getValue() const
Return the value of this Property as a QVariant. If the value has never been set, an invalid QVariant...
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
FloatProperty * point_world_size_property_
Property(const QString &name=QString(), const QVariant &default_value=QVariant(), const QString &description=QString(), Property *parent=nullptr)
Constructor.
BoolProperty(const QString &name=QString(), bool default_value=false, const QString &description=QString(), Property *parent=nullptr)
QMetaObject::Connection connect(const QObject *receiver, const char *slot, Qt::ConnectionType type=Qt::AutoConnection)
Connect changed() signal to given slot of receiver.
virtual void updateTopicFilter()
Property specialized to enforce floating point max/min.
MultiLayerDepth * ml_depth_data_
void setTopic(const QString &topic, const QString &datatype) override
Set the ROS topic to listen to for this display.
void hide()
Hide this Property in any PropertyTreeWidgets.
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
void enableOcclusionCompensation(bool occlusion_compensation)
void fillTransportOptionList(EnumProperty *property)
Fill list of available and working transport options.
const std::string & getFixedFrame()
Return the current fixed frame name.
void onInitialize() override
Override this function to do subclass-specific initialization.
virtual void updateOcclusionTimeOut()
virtual void updateTopic()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual float getFloat() const
virtual void expand()
Expand (show the children of) this Property.
RosFilteredTopicProperty * depth_topic_property_
virtual bool setValue(const QVariant &new_value)
Set the new value for this property. Returns true if the new value is different from the old value,...
BoolProperty * use_auto_size_property_
std::vector< TopicInfo > V_TopicInfo
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Ogre::Vector3 current_position_
std::string getStdString()
void scanForTransportSubscriberPlugins()
void caminfoCallback(sensor_msgs::CameraInfo::ConstPtr msg)
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
EnumProperty * depth_transport_property_
message_filters::Synchronizer< SyncPolicyDepthColor > SynchronizerDepthColor
EnumProperty * color_transport_property_
Displays a point cloud of type sensor_msgs::PointCloud.
BoolProperty * use_occlusion_compensation_property_
boost::shared_ptr< message_filters::Subscriber< sensor_msgs::CameraInfo > > cam_info_sub_
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
std::string getTopicStd() const
std::set< std::string > transport_plugin_types_
Ogre::Quaternion current_orientation_
boost::shared_ptr< image_transport::SubscriberFilter > depthmap_sub_
virtual void processMessage(const sensor_msgs::Image::ConstPtr &msg)
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Return the pose for a header, relative to the fixed frame, in Ogre classes.
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
Show status level and text, using a std::string. Convenience function which converts std::string to Q...
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
EnumProperty * color_transformer_property_
boost::shared_ptr< T > createInstance(const std::string &lookup_name)
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
void enableFilter(bool enabled)
boost::mutex cam_info_mutex_
~DepthCloudDisplay() override
boost::shared_ptr< tf2_ros::MessageFilter< sensor_msgs::Image > > depthmap_tf_filter_
bool setStdString(const std::string &std_str)
void setShadowTimeOut(double time_out)
virtual void reset()
Called to tell the display to clear its state.
virtual int getInt() const
Return the internal property value as an integer.
void reset() override
Called to tell the display to clear its state.
ros::NodeHandle threaded_nh_
A NodeHandle whose CallbackQueue is run from a different thread than the GUI.
sensor_msgs::CameraInfo::ConstPtr cam_info_
uint32_t messages_received_
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
RosFilteredTopicProperty * color_topic_property_
virtual void updateUseAutoSize()
std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr() const
Convenience function: returns getFrameManager()->getTF2BufferPtr().
FloatProperty * occlusion_shadow_timeout_property_
virtual void updateAutoSizeFactor()
FloatProperty * auto_size_factor_property_
Property specialized to provide max/min enforcement for integers.
std::vector< std::string > getDeclaredClasses()
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09