ImageDisplayBase::ImageDisplayBase() : Display() , it_(update_nh_) , sub_() , tf_filter_() , messages_received_(0) { topic_property_ = new RosTopicProperty("Image Topic", "", QString::fromStdString(ros::message_traits::datatype<sensor_msgs::Image>()), "sensor_msgs::Image topic to subscribe to.", this, SLOT( updateTopic() )); transport_property_ = new EnumProperty("Transport Hint", "raw", "Preferred method of sending images.", this, SLOT( updateTopic() )); connect(transport_property_, SIGNAL( requestOptions( EnumProperty* )), this, SLOT( fillTransportOptionList( EnumProperty* ))); queue_size_property_ = new IntProperty( "Queue Size", 2, "Advanced: set the size of the incoming message queue. Increasing this " "is useful if your incoming TF data is delayed significantly from your" " image data, but it can greatly increase memory usage if the messages are big.", this, SLOT( updateQueueSize() )); queue_size_property_->setMin( 1 ); transport_property_->setStdString("raw"); scanForTransportSubscriberPlugins(); }
DepthCloudDisplay::DepthCloudDisplay() : rviz::Display() , messages_received_(0) , depthmap_it_(update_nh_) , depthmap_sub_() , rgb_it_ (update_nh_) , rgb_sub_() , cameraInfo_sub_() , queue_size_(5) { // Depth map properties depth_topic_property_ = new RosTopicProperty("Depth Map Topic", "", QString::fromStdString(ros::message_traits::datatype<sensor_msgs::Image>()), "sensor_msgs::Image topic to subscribe to.", this, SLOT( updateTopic() )); depth_transport_property_ = new EnumProperty("Depth Map Transport Hint", "raw", "Preferred method of sending images.", this, SLOT( updateTopic() )); connect(depth_transport_property_, SIGNAL( requestOptions( EnumProperty* )), this, SLOT( fillTransportOptionList( EnumProperty* ))); depth_transport_property_->setStdString("raw"); // RGB image properties rgb_topic_property_ = new RosTopicProperty("RGB Image Topic", "", QString::fromStdString(ros::message_traits::datatype<sensor_msgs::Image>()), "sensor_msgs::Image topic to subscribe to.", this, SLOT( updateTopic() )); rgb_transport_property_ = new EnumProperty("RGB Transport Hint", "raw", "Preferred method of sending images.", this, SLOT( updateTopic() )); connect(rgb_transport_property_, SIGNAL( requestOptions( EnumProperty* )), this, SLOT( fillTransportOptionList( EnumProperty* ))); rgb_transport_property_->setStdString("raw"); // Queue size property queue_size_property_ = new IntProperty( "Queue Size", queue_size_, "Advanced: set the size of the incoming message queue. Increasing this " "is useful if your incoming TF data is delayed significantly from your" " image data, but it can greatly increase memory usage if the messages are big.", this, SLOT( updateQueueSize() )); queue_size_property_->setMin( 1 ); // Instantiate PointCloudCommon class for displaying point clouds pointcloud_common_ = new PointCloudCommon(this); // PointCloudCommon sets up a callback queue with a thread for each // instance. Use that for processing incoming messages. update_nh_.setCallbackQueue( pointcloud_common_->getCallbackQueue() ); // Scan for available transport plugins scanForTransportSubscriberPlugins(); }
ChangeDisplay::ChangeDisplay() : point_cloud_common_( new PointCloudCommon( this )) { queue_size_property_ = new IntProperty( "Queue Size", 10, "Advanced: set the size of the incoming PointCloud message queue. " " Increasing this is useful if your incoming TF data is delayed significantly " "from your PointCloud data, but it can greatly increase memory usage if the messages are big.", this, SLOT( updateQueueSize() )); // PointCloudCommon sets up a callback queue with a thread for each // instance. Use that for processing incoming messages. update_nh_.setCallbackQueue( point_cloud_common_->getCallbackQueue() ); }
MarkerDisplay::MarkerDisplay() : Display() { marker_topic_property_ = new RosTopicProperty( "Marker Topic", "visualization_marker", QString::fromStdString( ros::message_traits::datatype<visualization_msgs::Marker>() ), "visualization_msgs::Marker topic to subscribe to. <topic>_array will also" " automatically be subscribed with type visualization_msgs::MarkerArray.", this, SLOT( updateTopic() )); queue_size_property_ = new IntProperty( "Queue Size", 100, "Advanced: set the size of the incoming Marker message queue. Increasing this is" " useful if your incoming TF data is delayed significantly from your Marker data, " "but it can greatly increase memory usage if the messages are big.", this, SLOT( updateQueueSize() )); queue_size_property_->setMin( 0 ); namespaces_category_ = new Property( "Namespaces", QVariant(), "", this ); }
StereoImageDisplayBase::StereoImageDisplayBase() : Display() , left_sub_() , right_sub_() , left_tf_filter_() , right_tf_filter_() , messages_received_(0) , use_approx_sync_(false) { left_topic_property_ = new RosTopicProperty("Left Image Topic", "", QString::fromStdString(ros::message_traits::datatype<sensor_msgs::Image>()), "sensor_msgs::Image topic to subscribe to.", this, SLOT( updateTopics() )); right_topic_property_ = new RosTopicProperty("Right Image Topic", "", QString::fromStdString(ros::message_traits::datatype<sensor_msgs::Image>()), "sensor_msgs::Image topic to subscribe to.", this, SLOT( updateTopics() )); transport_property_ = new EnumProperty( "Transport Hint", "raw", "Preferred method of sending images.", this, SLOT( updateTopics() )); bool ok = connect(transport_property_, SIGNAL( requestOptions( EnumProperty* )), this, SLOT( fillTransportOptionList( EnumProperty* ))); Q_ASSERT(ok); queue_size_property_ = new IntProperty( "Queue Size", 2, "Advanced: set the size of the incoming message queue. Increasing this " "is useful if your incoming TF data is delayed significantly from your" " image data, but it can greatly increase memory usage if the messages are big.", this, SLOT( updateQueueSize() )); queue_size_property_->setMin( 1 ); approx_sync_property_ = new BoolProperty( "Approximate Sync", false, "Advanced: set this to true if your timestamps aren't synchronized.", this, SLOT( updateApproxSync() )); transport_property_->setStdString("raw"); }
CameraPub::CameraPub() : Display() , camera_trigger_name_("camera_trigger") , nh_() , new_caminfo_(false) , force_render_(false) , trigger_activated_(false) , last_image_publication_time_(0) , caminfo_ok_(false) , video_publisher_(0) { topic_property_ = new RosTopicProperty("Image Topic", "", QString::fromStdString(ros::message_traits::datatype<sensor_msgs::Image>()), "sensor_msgs::Image topic to publish to.", this, SLOT(updateTopic())); namespace_property_ = new StringProperty("Display namespace", "", "Namespace for this display.", this, SLOT(updateDisplayNamespace())); camera_info_property_ = new RosTopicProperty("Camera Info Topic", "", QString::fromStdString(ros::message_traits::datatype<sensor_msgs::CameraInfo>()), "sensor_msgs::CameraInfo topic to subscribe to.", this, SLOT(updateTopic())); queue_size_property_ = new IntProperty( "Queue Size", 2, "Advanced: set the size of the incoming message queue. Increasing this " "is useful if your incoming TF data is delayed significantly from your" " image data, but it can greatly increase memory usage if the messages are big.", this, SLOT(updateQueueSize())); queue_size_property_->setMin(1); frame_rate_property_ = new FloatProperty("Frame Rate", -1, "Sets target frame rate. Set to < 0 for maximum speed, set to 0 to stop, you can " "trigger single images with the /rviz_camera_trigger service.", this, SLOT(updateFrameRate())); frame_rate_property_->setMin(-1); background_color_property_ = new ColorProperty("Background Color", Qt::black, "Sets background color, values from 0.0 to 1.0.", this, SLOT(updateBackgroundColor())); }