30 #include <OgreSceneNode.h> 31 #include <OgreSceneManager.h> 51 "Advanced: set the size of the incoming FluidPressure message queue. " 52 " Increasing this is useful if your incoming TF data is delayed significantly " 53 "from your FluidPressure data, but it can greatly increase memory usage if the messages are big.",
88 sensor_msgs::PointCloud2Ptr filtered(
new sensor_msgs::PointCloud2);
91 sensor_msgs::PointField x;
94 x.datatype = sensor_msgs::PointField::FLOAT32;
96 sensor_msgs::PointField y;
99 y.datatype = sensor_msgs::PointField::FLOAT32;
101 sensor_msgs::PointField z;
104 z.datatype = sensor_msgs::PointField::FLOAT32;
106 sensor_msgs::PointField fluid_pressure;
107 fluid_pressure.name =
"fluid_pressure";
108 fluid_pressure.offset = 12;
109 fluid_pressure.datatype = sensor_msgs::PointField::FLOAT64;
110 fluid_pressure.count = 1;
113 filtered->header = msg->header;
114 filtered->fields.push_back(x);
115 filtered->fields.push_back(y);
116 filtered->fields.push_back(z);
117 filtered->fields.push_back(fluid_pressure);
118 filtered->data.resize(20);
119 const float zero_float = 0.0;
120 memcpy(&filtered->data[x.offset], &zero_float, 4);
121 memcpy(&filtered->data[y.offset], &zero_float, 4);
122 memcpy(&filtered->data[z.offset], &zero_float, 4);
123 memcpy(&filtered->data[fluid_pressure.offset], &msg->fluid_pressure, 8);
124 filtered->height = 1;
126 filtered->is_bigendian =
false;
127 filtered->point_step = 20;
128 filtered->row_step = 1;
tf2_ros::MessageFilter< sensor_msgs::FluidPressure > * tf_filter_
void onInitialize() override
Do initialization. Overridden from MessageFilterDisplay.
IntProperty * queue_size_property_
Displays an FluidPressure message of type sensor_msgs::FluidPressure.
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
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...
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
~FluidPressureDisplay() override
virtual void unsubscribe()
Property specialized to provide max/min enforcement for integers.
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
void processMessage(const sensor_msgs::FluidPressureConstPtr &msg) override
Process a single message. Overridden from MessageFilterDisplay.
Displays a point cloud of type sensor_msgs::PointCloud.
virtual Property * subProp(const QString &sub_name)
Return the first child Property with the given name, or the FailureProperty if no child has the name...
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
void setCallbackQueue(CallbackQueueInterface *queue)
virtual void setQueueSize(uint32_t new_queue_size)
void reset() override
Called to tell the display to clear its state.
virtual int getInt() const
Return the internal property value as an integer.
void onInitialize() override
void hide()
Hide this Property in any PropertyTreeWidgets.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
PointCloudCommon * point_cloud_common_
virtual ros::CallbackQueueInterface * getThreadedQueue()=0
Return a CallbackQueue using a different thread than the main GUI one.
void update(float wall_dt, float ros_dt)