mirror of
https://github.com/swri-robotics/mapviz.git
synced 2025-09-15 17:48:34 +08:00
Add clear history functionality.
This commit is contained in:
parent
a9799a6ba1
commit
a1c08fb105
@ -120,6 +120,7 @@ namespace mapviz
|
||||
void Hover(double x, double y, double scale);
|
||||
void Recenter();
|
||||
void HandleProfileTimer();
|
||||
void ClearHistory();
|
||||
|
||||
Q_SIGNALS:
|
||||
/**
|
||||
@ -144,7 +145,7 @@ namespace mapviz
|
||||
|
||||
QLabel* xy_pos_label_;
|
||||
QLabel* lat_lon_pos_label_;
|
||||
|
||||
|
||||
QWidget* spacer1_;
|
||||
QWidget* spacer2_;
|
||||
QWidget* spacer3_;
|
||||
@ -162,11 +163,11 @@ namespace mapviz
|
||||
bool force_480p_;
|
||||
bool resizable_;
|
||||
QColor background_;
|
||||
|
||||
|
||||
std::string capture_directory_;
|
||||
QThread video_thread_;
|
||||
VideoWriter* vid_writer_;
|
||||
|
||||
|
||||
bool updating_frames_;
|
||||
|
||||
ros::NodeHandle* node_;
|
||||
@ -191,7 +192,7 @@ namespace mapviz
|
||||
int draw_order = 0);
|
||||
|
||||
bool AddDisplay(
|
||||
AddMapvizDisplay::Request& req,
|
||||
AddMapvizDisplay::Request& req,
|
||||
AddMapvizDisplay::Response& resp);
|
||||
|
||||
void ClearDisplays();
|
||||
|
||||
@ -74,6 +74,8 @@ namespace mapviz
|
||||
|
||||
virtual void Shutdown() = 0;
|
||||
|
||||
virtual void ClearHistory() {}
|
||||
|
||||
/**
|
||||
* Draws on the Mapviz canvas using OpenGL commands; this will be called
|
||||
* before Paint();
|
||||
|
||||
@ -99,12 +99,12 @@ Mapviz::Mapviz(bool is_standalone, int argc, char** argv, QWidget *parent, Qt::W
|
||||
|
||||
ui_.statusbar->addPermanentWidget(xy_pos_label_);
|
||||
ui_.statusbar->addPermanentWidget(lat_lon_pos_label_);
|
||||
|
||||
|
||||
spacer1_ = new QWidget(ui_.statusbar);
|
||||
spacer1_->setMaximumSize(22,22);
|
||||
spacer1_->setMinimumSize(22,22);
|
||||
ui_.statusbar->addPermanentWidget(spacer1_);
|
||||
|
||||
|
||||
screenshot_button_ = new QPushButton();
|
||||
screenshot_button_->setMinimumSize(22, 22);
|
||||
screenshot_button_->setMaximumSize(22,22);
|
||||
@ -112,7 +112,7 @@ Mapviz::Mapviz(bool is_standalone, int argc, char** argv, QWidget *parent, Qt::W
|
||||
screenshot_button_->setFlat(true);
|
||||
screenshot_button_->setToolTip("Capture screenshot of display canvas");
|
||||
ui_.statusbar->addPermanentWidget(screenshot_button_);
|
||||
|
||||
|
||||
spacer2_ = new QWidget(ui_.statusbar);
|
||||
spacer2_->setMaximumSize(22,22);
|
||||
spacer2_->setMinimumSize(22,22);
|
||||
@ -126,7 +126,7 @@ Mapviz::Mapviz(bool is_standalone, int argc, char** argv, QWidget *parent, Qt::W
|
||||
rec_button_->setFlat(true);
|
||||
rec_button_->setToolTip("Start recording video of display canvas");
|
||||
ui_.statusbar->addPermanentWidget(rec_button_);
|
||||
|
||||
|
||||
stop_button_ = new QPushButton();
|
||||
stop_button_->setMinimumSize(22, 22);
|
||||
stop_button_->setMaximumSize(22,22);
|
||||
@ -171,6 +171,7 @@ Mapviz::Mapviz(bool is_standalone, int argc, char** argv, QWidget *parent, Qt::W
|
||||
connect(rec_button_, SIGNAL(toggled(bool)), this, SLOT(ToggleRecord(bool)));
|
||||
connect(stop_button_, SIGNAL(clicked()), this, SLOT(StopRecord()));
|
||||
connect(screenshot_button_, SIGNAL(clicked()), this, SLOT(Screenshot()));
|
||||
connect(ui_.actionClear_History, SIGNAL(triggered()), this, SLOT(ClearHistory()));
|
||||
|
||||
// Use a separate thread for writing video files so that it won't cause
|
||||
// lag on the main thread.
|
||||
@ -206,6 +207,14 @@ void Mapviz::showEvent(QShowEvent* event)
|
||||
void Mapviz::closeEvent(QCloseEvent* event)
|
||||
{
|
||||
AutoSave();
|
||||
|
||||
for (auto& display: plugins_)
|
||||
{
|
||||
MapvizPluginPtr plugin = display.second;
|
||||
canvas_->RemovePlugin(plugin);
|
||||
}
|
||||
|
||||
plugins_.clear();
|
||||
}
|
||||
|
||||
void Mapviz::Initialize()
|
||||
@ -257,7 +266,7 @@ void Mapviz::Initialize()
|
||||
canvas_->SetTargetFrame(ui_.targetframe->currentText().toStdString());
|
||||
|
||||
ros::NodeHandle priv("~");
|
||||
|
||||
|
||||
add_display_srv_ = node_->advertiseService("add_mapviz_display", &Mapviz::AddDisplay, this);
|
||||
|
||||
QProcessEnvironment env = QProcessEnvironment::systemEnvironment();
|
||||
@ -298,7 +307,7 @@ void Mapviz::Initialize()
|
||||
save_timer_.start(10000);
|
||||
connect(&save_timer_, SIGNAL(timeout()), this, SLOT(AutoSave()));
|
||||
}
|
||||
|
||||
|
||||
connect(&record_timer_, SIGNAL(timeout()), this, SLOT(CaptureVideoFrame()));
|
||||
|
||||
bool print_profile_data;
|
||||
@ -333,7 +342,7 @@ void Mapviz::UpdateFrames()
|
||||
tf_->getFrameStrings(frames);
|
||||
std::sort(frames.begin(), frames.end());
|
||||
|
||||
if (ui_.fixedframe->count() >= 0 &&
|
||||
if (ui_.fixedframe->count() >= 0 &&
|
||||
static_cast<size_t>(ui_.fixedframe->count()) == frames.size())
|
||||
{
|
||||
bool changed = false;
|
||||
@ -391,7 +400,7 @@ void Mapviz::UpdateFrames()
|
||||
index = ui_.targetframe->findText(current_target.c_str());
|
||||
ui_.targetframe->setCurrentIndex(index);
|
||||
}
|
||||
|
||||
|
||||
updating_frames_ = false;
|
||||
|
||||
if (current_target != ui_.targetframe->currentText().toStdString())
|
||||
@ -558,7 +567,7 @@ void Mapviz::Open(const std::string& filename)
|
||||
doc["fix_orientation"] >> fix_orientation;
|
||||
ui_.actionFix_Orientation->setChecked(fix_orientation);
|
||||
}
|
||||
|
||||
|
||||
if (swri_yaml_util::FindValue(doc, "rotate_90"))
|
||||
{
|
||||
bool rotate_90 = false;
|
||||
@ -586,7 +595,7 @@ void Mapviz::Open(const std::string& filename)
|
||||
doc["show_capture_tools"] >> show_capture_tools;
|
||||
ui_.actionShow_Capture_Tools->setChecked(show_capture_tools);
|
||||
}
|
||||
|
||||
|
||||
if (swri_yaml_util::FindValue(doc, "show_status_bar"))
|
||||
{
|
||||
bool show_status_bar = false;
|
||||
@ -646,12 +655,12 @@ void Mapviz::Open(const std::string& filename)
|
||||
ui_.actionForce_720p->setChecked(true);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
if (swri_yaml_util::FindValue(doc, "force_480p"))
|
||||
{
|
||||
bool force_480p;
|
||||
doc["force_480p"] >> force_480p;
|
||||
|
||||
|
||||
if (force_480p)
|
||||
{
|
||||
ui_.actionForce_480p->setChecked(true);
|
||||
@ -875,7 +884,7 @@ void Mapviz::SaveConfig()
|
||||
if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
|
||||
{
|
||||
std::string path = dialog.selectedFiles().first().toStdString();
|
||||
|
||||
|
||||
std::string title;
|
||||
size_t last_slash = path.find_last_of('/');
|
||||
if (last_slash != std::string::npos && last_slash != path.size() - 1)
|
||||
@ -889,13 +898,21 @@ void Mapviz::SaveConfig()
|
||||
}
|
||||
|
||||
title += " - mapviz";
|
||||
|
||||
|
||||
setWindowTitle(QString::fromStdString(title));
|
||||
|
||||
Save(path);
|
||||
}
|
||||
}
|
||||
|
||||
void Mapviz::ClearHistory()
|
||||
{
|
||||
for (auto& plugin: plugins_)
|
||||
{
|
||||
plugin.second->ClearHistory();
|
||||
}
|
||||
}
|
||||
|
||||
void Mapviz::SelectNewDisplay()
|
||||
{
|
||||
ROS_INFO("Select new display ...");
|
||||
@ -936,7 +953,7 @@ void Mapviz::SelectNewDisplay()
|
||||
}
|
||||
|
||||
bool Mapviz::AddDisplay(
|
||||
AddMapvizDisplay::Request& req,
|
||||
AddMapvizDisplay::Request& req,
|
||||
AddMapvizDisplay::Response& resp)
|
||||
{
|
||||
std::map<std::string, std::string> properties;
|
||||
@ -969,26 +986,26 @@ bool Mapviz::AddDisplay(
|
||||
{
|
||||
display.first->setData(Qt::UserRole, QVariant(req.draw_order - 1.1));
|
||||
ui_.configs->sortItems();
|
||||
|
||||
|
||||
ReorderDisplays();
|
||||
}
|
||||
else if (req.draw_order < 0)
|
||||
{
|
||||
display.first->setData(Qt::UserRole, QVariant(ui_.configs->count() + req.draw_order + 0.1));
|
||||
ui_.configs->sortItems();
|
||||
|
||||
|
||||
ReorderDisplays();
|
||||
}
|
||||
|
||||
|
||||
resp.success = true;
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
try
|
||||
{
|
||||
MapvizPluginPtr plugin =
|
||||
MapvizPluginPtr plugin =
|
||||
CreateNewDisplay(req.name, req.type, req.visible, false, req.draw_order);
|
||||
plugin->LoadConfig(config, "");
|
||||
plugin->DrawIcon();
|
||||
@ -1000,7 +1017,7 @@ bool Mapviz::AddDisplay(
|
||||
resp.success = false;
|
||||
resp.message = "Failed to load display plug-in.";
|
||||
}
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -1014,7 +1031,7 @@ void Mapviz::Hover(double x, double y, double scale)
|
||||
lat_lon_pos_label_->setVisible(false);
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
int32_t precision = static_cast<int32_t>(std::ceil(std::max(0.0, std::log10(1.0 / scale))));
|
||||
|
||||
QString text = ui_.fixedframe->currentText();
|
||||
@ -1028,50 +1045,50 @@ void Mapviz::Hover(double x, double y, double scale)
|
||||
x_ss << std::fixed << std::setprecision(precision);
|
||||
x_ss << x;
|
||||
text += x_ss.str().c_str();
|
||||
|
||||
|
||||
text += ", ";
|
||||
|
||||
|
||||
std::ostringstream y_ss;
|
||||
y_ss << std::fixed << std::setprecision(precision);
|
||||
y_ss << y;
|
||||
text += y_ss.str().c_str();
|
||||
|
||||
|
||||
xy_pos_label_->setText(text);
|
||||
xy_pos_label_->setVisible(true);
|
||||
xy_pos_label_->update();
|
||||
|
||||
|
||||
swri_transform_util::Transform transform;
|
||||
if (tf_manager_.SupportsTransform(
|
||||
swri_transform_util::_wgs84_frame,
|
||||
swri_transform_util::_wgs84_frame,
|
||||
ui_.fixedframe->currentText().toStdString()) &&
|
||||
tf_manager_.GetTransform(
|
||||
swri_transform_util::_wgs84_frame,
|
||||
swri_transform_util::_wgs84_frame,
|
||||
ui_.fixedframe->currentText().toStdString(),
|
||||
transform))
|
||||
{
|
||||
tf::Vector3 point(x, y, 0);
|
||||
point = transform * point;
|
||||
|
||||
|
||||
QString lat_lon_text = "lat/lon: ";
|
||||
|
||||
|
||||
double lat_scale = (1.0 / 111111.0) * scale;
|
||||
int32_t lat_precision = static_cast<int32_t>(std::ceil(std::max(0.0, std::log10(1.0 / lat_scale))));
|
||||
|
||||
|
||||
std::ostringstream lat_ss;
|
||||
lat_ss << std::fixed << std::setprecision(lat_precision);
|
||||
lat_ss << point.y();
|
||||
lat_lon_text += lat_ss.str().c_str();
|
||||
|
||||
|
||||
lat_lon_text += ", ";
|
||||
|
||||
|
||||
double lon_scale = (1.0 / (111111.0 * std::cos(point.y() * swri_math_util::_deg_2_rad))) * scale;
|
||||
int32_t lon_precision = static_cast<int32_t>(std::ceil(std::max(0.0, std::log10(1.0 / lon_scale))));
|
||||
|
||||
|
||||
std::ostringstream lon_ss;
|
||||
lon_ss << std::fixed << std::setprecision(lon_precision);
|
||||
lon_ss << point.x();
|
||||
lat_lon_text += lon_ss.str().c_str();
|
||||
|
||||
|
||||
lat_lon_pos_label_->setText(lat_lon_text);
|
||||
lat_lon_pos_label_->setVisible(true);
|
||||
lat_lon_pos_label_->update();
|
||||
@ -1106,17 +1123,17 @@ MapvizPluginPtr Mapviz::CreateNewDisplay(
|
||||
|
||||
ROS_INFO("creating: %s", real_type.c_str());
|
||||
MapvizPluginPtr plugin = loader_->createInstance(real_type.c_str());
|
||||
|
||||
|
||||
// Setup configure widget
|
||||
config_item->SetWidget(plugin->GetConfigWidget(this));
|
||||
plugin->SetIcon(config_item->ui_.icon);
|
||||
|
||||
|
||||
plugin->Initialize(tf_, canvas_);
|
||||
plugin->SetType(real_type.c_str());
|
||||
plugin->SetName(name);
|
||||
plugin->SetNode(*node_);
|
||||
plugin->SetVisible(visible);
|
||||
|
||||
|
||||
if (draw_order == 0)
|
||||
{
|
||||
plugin->SetDrawOrder(ui_.configs->count());
|
||||
@ -1159,7 +1176,7 @@ MapvizPluginPtr Mapviz::CreateNewDisplay(
|
||||
{
|
||||
ui_.configs->insertItem(plugin->DrawOrder(), item);
|
||||
}
|
||||
|
||||
|
||||
ui_.configs->setItemWidget(item, config_item);
|
||||
ui_.configs->UpdateIndices();
|
||||
|
||||
@ -1262,7 +1279,7 @@ void Mapviz::ToggleCaptureTools(bool on)
|
||||
{
|
||||
ui_.actionShow_Status_Bar->setChecked(true);
|
||||
}
|
||||
|
||||
|
||||
screenshot_button_->setVisible(on);
|
||||
rec_button_->setVisible(on);
|
||||
stop_button_->setVisible(on);
|
||||
@ -1283,9 +1300,9 @@ void Mapviz::ToggleRecord(bool on)
|
||||
{
|
||||
// Lock the window size.
|
||||
AdjustWindowSize();
|
||||
|
||||
|
||||
canvas_->CaptureFrames(true);
|
||||
|
||||
|
||||
std::string posix_time = boost::posix_time::to_iso_string(ros::WallTime::now().toBoost());
|
||||
boost::replace_all(posix_time, ".", "_");
|
||||
std::string filename = capture_directory_ + "/mapviz_" + posix_time + ".avi";
|
||||
@ -1298,13 +1315,13 @@ void Mapviz::ToggleRecord(bool on)
|
||||
StopRecord();
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
ROS_INFO("Writing video to: %s", filename.c_str());
|
||||
ui_.statusbar->showMessage("Recording video to " + QString::fromStdString(filename));
|
||||
|
||||
|
||||
canvas_->updateGL();
|
||||
}
|
||||
|
||||
|
||||
record_timer_.start(1000.0 / 30.0);
|
||||
}
|
||||
else
|
||||
@ -1371,41 +1388,41 @@ void Mapviz::StopRecord()
|
||||
{
|
||||
rec_button_->setChecked(false);
|
||||
stop_button_->setEnabled(false);
|
||||
|
||||
|
||||
record_timer_.stop();
|
||||
if (vid_writer_)
|
||||
{
|
||||
vid_writer_->stop();
|
||||
}
|
||||
canvas_->CaptureFrames(false);
|
||||
|
||||
|
||||
ui_.statusbar->showMessage(QString(""));
|
||||
rec_button_->setToolTip("Start recording video of display canvas");
|
||||
|
||||
|
||||
AdjustWindowSize();
|
||||
}
|
||||
|
||||
void Mapviz::Screenshot()
|
||||
{
|
||||
canvas_->CaptureFrame(true);
|
||||
|
||||
|
||||
std::vector<uint8_t> frame;
|
||||
if (canvas_->CopyCaptureBuffer(frame))
|
||||
{
|
||||
cv::Mat image(canvas_->height(), canvas_->width(), CV_8UC4, &frame[0]);
|
||||
cv::Mat screenshot;
|
||||
cvtColor(image, screenshot, CV_BGRA2BGR);
|
||||
|
||||
|
||||
cv::flip(screenshot, screenshot, 0);
|
||||
|
||||
|
||||
std::string posix_time = boost::posix_time::to_iso_string(ros::WallTime::now().toBoost());
|
||||
boost::replace_all(posix_time, ".", "_");
|
||||
boost::replace_all(posix_time, ".", "_");
|
||||
std::string filename = capture_directory_ + "/mapviz_" + posix_time + ".png";
|
||||
boost::replace_all(filename, "~", getenv("HOME"));
|
||||
|
||||
ROS_INFO("Writing screenshot to: %s", filename.c_str());
|
||||
|
||||
ROS_INFO("Writing screenshot to: %s", filename.c_str());
|
||||
ui_.statusbar->showMessage("Saved image to " + QString::fromStdString(filename));
|
||||
|
||||
|
||||
cv::imwrite(filename, screenshot);
|
||||
}
|
||||
else
|
||||
|
||||
@ -31,7 +31,7 @@
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>27</height>
|
||||
<height>20</height>
|
||||
</rect>
|
||||
</property>
|
||||
<widget class="QMenu" name="menuFile">
|
||||
@ -62,8 +62,15 @@
|
||||
<addaction name="actionShow_Capture_Tools"/>
|
||||
<addaction name="separator"/>
|
||||
</widget>
|
||||
<widget class="QMenu" name="menuData">
|
||||
<property name="title">
|
||||
<string>Data</string>
|
||||
</property>
|
||||
<addaction name="actionClear_History"/>
|
||||
</widget>
|
||||
<addaction name="menuFile"/>
|
||||
<addaction name="menu_View"/>
|
||||
<addaction name="menuData"/>
|
||||
</widget>
|
||||
<widget class="QStatusBar" name="statusbar">
|
||||
<property name="enabled">
|
||||
@ -471,6 +478,11 @@
|
||||
<string>Image Transport</string>
|
||||
</property>
|
||||
</action>
|
||||
<action name="actionClear_History">
|
||||
<property name="text">
|
||||
<string>Clear History</string>
|
||||
</property>
|
||||
</action>
|
||||
</widget>
|
||||
<customwidgets>
|
||||
<customwidget>
|
||||
|
||||
@ -71,6 +71,8 @@ namespace mapviz_plugins
|
||||
{
|
||||
}
|
||||
|
||||
void ClearHistory();
|
||||
|
||||
void Draw(double x, double y, double scale);
|
||||
|
||||
void Transform();
|
||||
|
||||
@ -70,6 +70,8 @@ namespace mapviz_plugins
|
||||
bool Initialize(QGLWidget* canvas);
|
||||
void Shutdown() {}
|
||||
|
||||
void ClearHistory();
|
||||
|
||||
void Draw(double x, double y, double scale);
|
||||
void Paint(QPainter* painter, double x, double y, double scale);
|
||||
|
||||
|
||||
@ -80,6 +80,9 @@ namespace mapviz_plugins
|
||||
virtual ~PointDrawingPlugin()
|
||||
{
|
||||
}
|
||||
|
||||
void ClearHistory();
|
||||
|
||||
virtual void Transform();
|
||||
virtual bool DrawPoints(double scale);
|
||||
virtual bool DrawArrows();
|
||||
|
||||
@ -75,6 +75,9 @@ namespace mapviz_plugins
|
||||
void Shutdown()
|
||||
{
|
||||
}
|
||||
|
||||
void ClearHistory();
|
||||
|
||||
void Draw(double x, double y, double scale);
|
||||
|
||||
void Transform();
|
||||
|
||||
@ -74,6 +74,8 @@ namespace mapviz_plugins
|
||||
bool Initialize(QGLWidget* canvas);
|
||||
void Shutdown() {}
|
||||
|
||||
void ClearHistory();
|
||||
|
||||
void Draw(double x, double y, double scale);
|
||||
|
||||
void Transform();
|
||||
|
||||
@ -159,6 +159,11 @@ namespace mapviz_plugins
|
||||
{
|
||||
}
|
||||
|
||||
void LaserScanPlugin::ClearHistory()
|
||||
{
|
||||
scans_.clear();
|
||||
}
|
||||
|
||||
void LaserScanPlugin::DrawIcon()
|
||||
{
|
||||
if (icon_)
|
||||
|
||||
@ -87,6 +87,11 @@ namespace mapviz_plugins
|
||||
{
|
||||
}
|
||||
|
||||
void MarkerPlugin::ClearHistory()
|
||||
{
|
||||
markers_.clear();
|
||||
}
|
||||
|
||||
void MarkerPlugin::SelectTopic()
|
||||
{
|
||||
ros::master::TopicInfo topic = mapviz::SelectTopicDialog::selectTopic(
|
||||
|
||||
@ -59,6 +59,11 @@ namespace mapviz_plugins
|
||||
{
|
||||
}
|
||||
|
||||
void PointDrawingPlugin::ClearHistory()
|
||||
{
|
||||
points_.clear();
|
||||
}
|
||||
|
||||
void PointDrawingPlugin::DrawIcon()
|
||||
{
|
||||
if (icon_)
|
||||
|
||||
@ -172,6 +172,11 @@ namespace mapviz_plugins
|
||||
{
|
||||
}
|
||||
|
||||
void PointCloud2Plugin::ClearHistory()
|
||||
{
|
||||
scans_.clear();
|
||||
}
|
||||
|
||||
void PointCloud2Plugin::DrawIcon()
|
||||
{
|
||||
if (icon_)
|
||||
|
||||
@ -97,6 +97,11 @@ namespace mapviz_plugins
|
||||
{
|
||||
}
|
||||
|
||||
void TexturedMarkerPlugin::ClearHistory()
|
||||
{
|
||||
markers_.clear();
|
||||
}
|
||||
|
||||
void TexturedMarkerPlugin::SelectTopic()
|
||||
{
|
||||
ros::master::TopicInfo topic = mapviz::SelectTopicDialog::selectTopic(
|
||||
|
||||
Loading…
Reference in New Issue
Block a user