42#include <rviz_common/display_context.hpp>
43#include <rviz_common/window_manager_interface.hpp>
46#include <QInputDialog>
48#include "ui_motion_planning_rviz_plugin_frame.h"
53void MotionPlanningFrame::databaseConnectButtonClicked()
58void MotionPlanningFrame::planningPipelineIndexChanged(
int index)
71void MotionPlanningFrame::planningAlgorithmIndexChanged(
int index)
73 std::string planner_id =
ui_->planning_algorithm_combo_box->itemText(index).toStdString();
77 ui_->planner_param_treeview->setPlannerId(planner_id);
83void MotionPlanningFrame::resetDbButtonClicked()
85 if (QMessageBox::warning(
this,
"Data about to be deleted",
86 "The following dialog will allow you to drop a MoveIt "
87 "Warehouse database. Are you sure you want to continue?",
88 QMessageBox::Yes | QMessageBox::No) == QMessageBox::No)
92 dbs.append(
"Planning Scenes");
93 dbs.append(
"Constraints");
94 dbs.append(
"Robot States");
98 QInputDialog::getItem(
this, tr(
"Select Database"), tr(
"Choose the database to reset:"), dbs, 2,
false, &ok);
102 if (QMessageBox::critical(
103 this,
"Data about to be deleted",
104 QString(
"All data in database '").
append(response).
append(
"'. Are you sure you want to continue?"),
105 QMessageBox::Yes | QMessageBox::No) == QMessageBox::No)
112void MotionPlanningFrame::computeDatabaseConnectButtonClicked()
114 RCLCPP_INFO(logger_,
"Connect to database: {host: %s, port: %d}",
ui_->database_host->text().toStdString().c_str(),
115 ui_->database_port->value());
129 conn->setParams(
ui_->database_host->text().toStdString(),
ui_->database_port->value(), 5.0);
142 catch (std::exception& ex)
145 RCLCPP_ERROR(logger_,
"%s", ex.what());
152void MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper(
int mode)
156 ui_->planning_scene_tree->setUpdatesEnabled(
false);
157 ui_->planning_scene_tree->clear();
158 ui_->planning_scene_tree->setUpdatesEnabled(
true);
160 ui_->database_connect_button->setUpdatesEnabled(
false);
161 ui_->database_connect_button->setText(QString::fromStdString(
"Connect"));
162 ui_->database_connect_button->setStyleSheet(
"QPushButton { color : green }");
163 ui_->database_connect_button->setUpdatesEnabled(
true);
164 ui_->reset_db_button->hide();
166 ui_->load_scene_button->setEnabled(
false);
167 ui_->load_query_button->setEnabled(
false);
168 ui_->save_query_button->setEnabled(
false);
169 ui_->save_scene_button->setEnabled(
false);
170 ui_->delete_query_button->setEnabled(
false);
171 ui_->delete_scene_button->setEnabled(
false);
172 populateConstraintsList(std::vector<std::string>());
176 ui_->database_connect_button->setUpdatesEnabled(
false);
177 ui_->database_connect_button->setText(QString::fromStdString(
"Connecting ..."));
178 ui_->database_connect_button->setUpdatesEnabled(
true);
179 populateConstraintsList(std::vector<std::string>());
183 ui_->database_connect_button->setUpdatesEnabled(
false);
184 ui_->database_connect_button->setText(QString::fromStdString(
"Connect"));
185 ui_->database_connect_button->setStyleSheet(
"QPushButton { color : green }");
186 ui_->database_connect_button->setUpdatesEnabled(
true);
187 ui_->reset_db_button->hide();
191 ui_->database_connect_button->setUpdatesEnabled(
false);
192 ui_->database_connect_button->setText(QString::fromStdString(
"Disconnect"));
193 ui_->database_connect_button->setStyleSheet(
"QPushButton { color : darkBlue }");
194 ui_->database_connect_button->setUpdatesEnabled(
true);
195 ui_->save_scene_button->setEnabled(
true);
196 ui_->reset_db_button->show();
197 populatePlanningSceneTreeView();
198 loadStoredStates(
".*");
201 move_group_->setConstraintsDatabase(
ui_->database_host->text().toStdString(),
ui_->database_port->value());
207void MotionPlanningFrame::computeResetDbButtonClicked(
const std::string& db)
217 else if (db ==
"Planning Scenes")
moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage_
Ui::MotionPlanningUI * ui_
std::vector< moveit_msgs::msg::PlannerInterfaceDescription > planner_descriptions_
moveit_warehouse::ConstraintsStoragePtr constraints_storage_
moveit::planning_interface::MoveGroupInterfacePtr move_group_
MotionPlanningDisplay * planning_display_
moveit_warehouse::RobotStateStoragePtr robot_state_storage_
void addMainLoopJob(const std::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called
void addBackgroundJob(const std::function< void()> &job, const std::string &name)
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
std::string append(const std::string &left, const std::string &right)