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_);
 }
Example #2
0
void MainWindow::loadSettings(){
    setFullScreen(false);
    setHideMenu(false);

    QSettings settingsNative;

    resize(settingsNative.value("size", QSize(320, 480 + ui.menuBar->height())).toSize());
    move(settingsNative.value("pos",    QPoint(0, 0)).toPoint());

    int red = settingsNative.value("backgroundRed",     240).toInt();
    int green = settingsNative.value("backgroundGreen", 240).toInt();
    int blue = settingsNative.value("backgroundBlue",   240).toInt();
    QColor backgroundColor = QColor(red, green, blue);

    red = settingsNative.value("canvasRed",     255).toInt();
    green = settingsNative.value("canvasGreen", 255).toInt();
    blue = settingsNative.value("canvasBlue",   255).toInt();
    QColor canvasColor = QColor(red, green, blue);

    red = settingsNative.value("infoRed",     0).toInt();
    green = settingsNative.value("infoGreen", 0).toInt();
    blue = settingsNative.value("infoBlue",   0).toInt();
    QColor infoColor = QColor(red, green, blue);

    setBackgroundColor(backgroundColor);
    setCanvasColor(canvasColor);
    setInfoColor(infoColor);

    updateBackgroundColor();
    updateCanvasColor();
    updateInfoColor();

    QSettings settings(Constants::SETTINGS_FOLDER + "/" + Constants::PLAYER_SETTINGS_FILE, QSettings::IniFormat);

    setWidth(settings.value("width",             320).toInt());
    setHeight(settings.value("height",           480).toInt());
    setScale(settings.value("scale",             100).toInt());
    setFps(settings.value("fps",                 60).toInt());
    setOrientation(static_cast<Orientation>(settings.value("orientation", ePortrait).toInt()));
    setDrawInfos(settings.value("drawInfos",     false).toBool());
    setAutoScale(settings.value("autoScale",     false).toBool());
    setAlwaysOnTop(settings.value("alwaysOnTop", false).toBool());

    checkLoadedSettings();

    updateFps();
    updateDrawInfos();
    updateAlwaysOnTop();
    updateAutoScale();
    updateOrientation();
    updateResolution();
}
Example #3
0
void MainWindow::fullScreenWindow(bool _fullScreen){
    setAutoScale(_fullScreen);
    setFullScreen(_fullScreen);
    actionFull_Screen(fullScreen());
    updateAutoScale();
}
Example #4
0
void MainWindow::actionAuto_Scale(bool checked){
    setAutoScale(checked);

    updateAutoScale();
}
 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()));
 }