void PieChartDisplay::onInitialize()
 {
   static int count = 0;
   rviz::UniformStringStream ss;
   ss << "PieChartDisplayObject" << count++;
   overlay_.reset(new OverlayObject(ss.str()));
   onEnable();
   updateSize();
   updateLeft();
   updateTop();
   updateFGColor();
   updateBGColor();
   updateFGAlpha();
   updateFGAlpha2();
   updateBGAlpha();
   updateMinValue();
   updateMaxValue();
   updateTextColor();
   updateTextAlpha();
   updateTextSize();
   updateShowCaption();
   updateAutoColorChange();
   updateMaxColor();
   overlay_->updateTextureSize(texture_size_, texture_size_ + caption_offset_);
   overlay_->hide();
 }
 void Plotter2DDisplay::onInitialize()
 {
   static int count = 0;
   rviz::UniformStringStream ss;
   ss << "Plotter2DDisplayObject" << count++;
   overlay_.reset(new OverlayObject(ss.str()));
   updateBufferSize();
   onEnable();
   updateShowValue();
   updateWidth();
   updateHeight();
   updateLeft();
   updateTop();
   updateFGColor();
   updateBGColor();
   updateFGAlpha();
   updateBGAlpha();
   updateLineWidth();
   updateUpdateInterval();
   updateShowBorder();
   updateAutoColorChange();
   updateMaxColor();
   updateShowCaption();
   updateTextSize();
   updateAutoScale();
   updateMinValue();
   updateMaxValue();
   overlay_->updateTextureSize(width_property_->getInt(),
                               height_property_->getInt() + caption_offset_);
 }
 void Plotter2DDisplay::updateAutoScale()
 {
   auto_scale_ = auto_scale_property_->getBool();
   if (auto_scale_) {
     min_value_property_->hide();
     max_value_property_->hide();
   }
   else {
     min_value_property_->show();
     max_value_property_->show();
   }
   updateMinValue();
   updateMaxValue();
 }
  PieChartDisplay::PieChartDisplay()
    : rviz::Display()
  {
    update_topic_property_ = new rviz::RosTopicProperty(
      "Topic", "",
      ros::message_traits::datatype<std_msgs::Float32>(),
      "std_msgs::Float32 topic to subscribe to.",
      this, SLOT( updateTopic() ));
    size_property_ = new rviz::IntProperty("size", 128,
                                           "size of the plotter window",
                                           this, SLOT(updateSize()));
    left_property_ = new rviz::IntProperty("left", 128,
                                           "left of the plotter window",
                                           this, SLOT(updateLeft()));
    top_property_ = new rviz::IntProperty("top", 128,
                                          "top of the plotter window",
                                          this, SLOT(updateTop()));
    fg_color_property_ = new rviz::ColorProperty("foreground color",
                                                 QColor(25, 255, 240),
                                                 "color to draw line",
                                                 this, SLOT(updateFGColor()));
    fg_alpha_property_
      = new rviz::FloatProperty("foreground alpha", 0.7,
                                "alpha belnding value for foreground",
                                this, SLOT(updateFGAlpha()));
    fg_alpha2_property_
      = new rviz::FloatProperty("foreground alpha 2", 0.4,
                                "alpha belnding value for foreground for indicator",
                                this, SLOT(updateFGAlpha2()));
    bg_color_property_ = new rviz::ColorProperty("background color",
                                                 QColor(0, 0, 0),
                                                 "background color",
                                                 this, SLOT(updateBGColor()));
    bg_alpha_property_
      = new rviz::FloatProperty("backround alpha", 0.0,
                                "alpha belnding value for background",
                                this, SLOT(updateBGAlpha()));
    text_color_property_
      = new rviz::ColorProperty("text color",
                                QColor(25, 255, 240),
                                "text color",
                                this, SLOT(updateTextColor()));
    text_alpha_property_
      = new rviz::FloatProperty("text alpha", 1.0,
                                "alpha belnding value for text",
                                this, SLOT(updateTextAlpha()));
    text_size_property_
      = new rviz::IntProperty("text size", 14,
                              "text size",
                              this, SLOT(updateTextSize()));
    show_caption_property_
      = new rviz::BoolProperty("show caption", true,
                                "show caption",
                                this, SLOT(updateShowCaption()));
    max_value_property_
      = new rviz::FloatProperty("max value", 1.0,
                                "max value of pie chart",
                                this, SLOT(updateMaxValue()));
    min_value_property_
      = new rviz::FloatProperty("min value", 0.0,
                                "min value of pie chart",
                                this, SLOT(updateMinValue()));
    auto_color_change_property_
      = new rviz::BoolProperty("auto color change",
                               false,
                               "change the color automatically",
                               this, SLOT(updateAutoColorChange()));
    max_color_property_
      = new rviz::ColorProperty("max color",
                                QColor(255, 0, 0),
                                "only used if auto color change is set to True.",
                                this, SLOT(updateMaxColor()));

  }
Ejemplo n.º 5
0
pChunk DrawnWaveform::
        operator()( Signal::pMonoBuffer b )
{
    float blobsize = blob(b->sample_rate());

    unsigned w = ((unsigned)(b->number_of_samples() / blobsize / drawWaveform_BLOCK_SIZE)) *drawWaveform_BLOCK_SIZE;

    if (0 == w)
        throw std::logic_error("DrawnWaveform::operator() Not enough data");

    size_t free = availableMemoryForSingleAllocation();

    free /= 2; // Don't even try to get close to use all memory
    // never use more than 64 MB
    if (free > 64<<20)
        free = 64<<20;

    unsigned wmax = free/(drawWaveform_YRESOLUTION*sizeof(Tfr::ChunkElement)*drawWaveform_BLOCK_SIZE ) * drawWaveform_BLOCK_SIZE;
    if (0==wmax)
        wmax = free/(drawWaveform_YRESOLUTION*sizeof(Tfr::ChunkElement));
    if (0==wmax)
        wmax = 1;
    if (wmax < w)
        w = wmax;

    updateMaxValue(b);

    pChunk c(new DrawnWaveformChunk(this->block_fs));
    c->transform_data.reset( new ChunkData(w, drawWaveform_YRESOLUTION, 1));

    unsigned readstop = b->number_of_samples();
    if (b->getInterval().last > signal_length)
    {
        if (b->getInterval().first > signal_length)
            readstop = 0;
        else
            readstop = signal_length - b->getInterval().first;
    }

    float writeposoffs = ((b->sample_offset() / blobsize) - floorf((b->sample_offset() / blobsize).asFloat())).asFloat();
    ::drawWaveform(
            b->waveform_data(),
            c->transform_data,
            blobsize,
            readstop,
            maxValue,
            writeposoffs);

    this->block_fs = 0;

    c->chunk_offset = b->sample_offset() / blobsize + writeposoffs;
    c->freqAxis = freqAxis( b->sample_rate() );

    c->first_valid_sample = 0;
    c->n_valid_samples = c->nSamples();

    c->original_sample_rate = b->sample_rate();
    c->sample_rate = b->sample_rate() / blobsize;

    return c;
}
 Plotter2DDisplay::Plotter2DDisplay()
   : rviz::Display(), min_value_(0.0), max_value_(0.0)
 {
   update_topic_property_ = new rviz::RosTopicProperty(
     "Topic", "",
     ros::message_traits::datatype<std_msgs::Float32>(),
     "std_msgs::Float32 topic to subscribe to.",
     this, SLOT(updateTopic()));
   show_value_property_ = new rviz::BoolProperty(
     "Show Value", true,
     "Show value on plotter",
     this, SLOT(updateShowValue()));
   buffer_length_property_ = new rviz::IntProperty(
     "Buffer length", 100,
     ros::message_traits::datatype<std_msgs::Float32>(),
     this, SLOT(updateBufferSize()));
   width_property_ = new rviz::IntProperty("width", 128,
                                           "width of the plotter window",
                                           this, SLOT(updateWidth()));
   width_property_->setMin(1);
   width_property_->setMax(2000);
   height_property_ = new rviz::IntProperty("height", 128,
                                            "height of the plotter window",
                                            this, SLOT(updateHeight()));
   height_property_->setMin(1);
   height_property_->setMax(2000);
   left_property_ = new rviz::IntProperty("left", 128,
                                          "left of the plotter window",
                                          this, SLOT(updateLeft()));
   left_property_->setMin(0);
   top_property_ = new rviz::IntProperty("top", 128,
                                         "top of the plotter window",
                                         this, SLOT(updateTop()));
   top_property_->setMin(0);
   auto_scale_property_ = new rviz::BoolProperty(
     "auto scale", true,
     "enable auto scale",
     this, SLOT(updateAutoScale()));
   max_value_property_ = new rviz::FloatProperty(
     "max value", 1.0,
     "max value, used only if auto scale is disabled",
     this, SLOT(updateMaxValue()));
   min_value_property_ = new rviz::FloatProperty(
     "min value", -1.0,
     "min value, used only if auto scale is disabled",
     this, SLOT(updateMinValue()));
   fg_color_property_ = new rviz::ColorProperty(
     "foreground color", QColor(25, 255, 240),
     "color to draw line",
     this, SLOT(updateFGColor()));
   fg_alpha_property_ = new rviz::FloatProperty(
     "foreground alpha", 0.7,
     "alpha belnding value for foreground",
     this, SLOT(updateFGAlpha()));
   fg_alpha_property_->setMin(0);
   fg_alpha_property_->setMax(1.0);
   bg_color_property_ = new rviz::ColorProperty(
     "background color", QColor(0, 0, 0),
     "background color",
     this, SLOT(updateBGColor()));
   bg_alpha_property_ = new rviz::FloatProperty(
     "backround alpha", 0.0,
     "alpha belnding value for background",
     this, SLOT(updateBGAlpha()));
   bg_alpha_property_->setMin(0);
   bg_alpha_property_->setMax(1.0);
   line_width_property_ = new rviz::IntProperty("linewidth", 1,
                                                "linewidth of the plot",
                                                this, SLOT(updateLineWidth()));
   line_width_property_->setMin(1);
   line_width_property_->setMax(1000);
   show_border_property_ = new rviz::BoolProperty(
     "border", true,
     "show border or not",
     this, SLOT(updateShowBorder()));
   text_size_property_ = new rviz::IntProperty("text size", 12,
                                               "text size of the caption",
                                               this, SLOT(updateTextSize()));
   text_size_property_->setMin(1);
   text_size_property_->setMax(1000);
   show_caption_property_ = new rviz::BoolProperty(
     "caption", true,
     "show caption or not",
     this, SLOT(updateShowCaption()));
   update_interval_property_ = new rviz::FloatProperty(
     "update interval", 0.04,
     "update interval of the plotter",
     this, SLOT(updateUpdateInterval()));
   update_interval_property_->setMin(0.0);
   update_interval_property_->setMax(100);
   auto_color_change_property_
     = new rviz::BoolProperty("auto color change",
                              false,
                              "change the color automatically",
                              this, SLOT(updateAutoColorChange()));
   max_color_property_
     = new rviz::ColorProperty(
       "max color",
       QColor(255, 0, 0),
       "only used if auto color change is set to True.",
       this, SLOT(updateMaxColor()));
 }