43#include <QInputDialog>
45#include "ui_motion_planning_rviz_plugin_frame.h"
50void MotionPlanningFrame::populateRobotStatesList()
52 ui_->list_states->clear();
53 for (std::pair<const std::string, moveit_msgs::msg::RobotState>& robot_state :
robot_states_)
55 QListWidgetItem* item =
new QListWidgetItem(QString(robot_state.first.c_str()));
56 ui_->list_states->addItem(item);
60void MotionPlanningFrame::loadStateButtonClicked()
67 QInputDialog::getText(
this, tr(
"Robot states to load"), tr(
"Pattern:"), QLineEdit::Normal,
".*", &ok);
68 if (ok && !
text.isEmpty())
70 loadStoredStates(
text.toStdString());
75 QMessageBox::warning(
this,
"Warning",
"Not connected to a database.");
79void MotionPlanningFrame::loadStoredStates(
const std::string& pattern)
81 std::vector<std::string> names;
86 catch (std::exception& ex)
88 QMessageBox::warning(
this,
"Cannot query the database",
89 QString(
"Wrongly formatted regular expression for robot states: ").
append(ex.what()));
93 clearStatesButtonClicked();
95 for (
const std::string& name : names)
98 bool got_state =
false;
103 catch (std::exception& ex)
105 RCLCPP_ERROR(logger_,
"%s", ex.what());
119 populateRobotStatesList();
126 std::stringstream ss;
130 QString
text = QInputDialog::getText(
this, tr(
"Choose a name"), tr(
"State name:"), QLineEdit::Normal,
131 QString(ss.str().c_str()), &ok);
141 QMessageBox::warning(
this,
"Name already exists",
142 QString(
"The name '").
append(
name.c_str()).append(
"' already exists. Not creating state."));
147 moveit_msgs::msg::RobotState msg;
158 catch (std::exception& ex)
160 RCLCPP_ERROR(logger_,
"Cannot save robot state on the database: %s", ex.what());
165 QMessageBox::warning(
this,
"Warning",
"Not connected to a database. The state will be created but not stored");
170 QMessageBox::warning(
this,
"Start state not saved",
"Cannot use an empty name for a new start state.");
172 populateRobotStatesList();
175void MotionPlanningFrame::saveStartStateButtonClicked()
180void MotionPlanningFrame::saveGoalStateButtonClicked()
185void MotionPlanningFrame::setAsStartStateButtonClicked()
187 QListWidgetItem* item =
ui_->list_states->currentItem();
197void MotionPlanningFrame::setAsGoalStateButtonClicked()
199 QListWidgetItem* item =
ui_->list_states->currentItem();
209void MotionPlanningFrame::removeStateButtonClicked()
215 msg_box.setText(
"All the selected states will be removed from the database");
216 msg_box.setInformativeText(
"Do you want to continue?");
217 msg_box.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
218 msg_box.setDefaultButton(QMessageBox::No);
219 int ret = msg_box.exec();
223 case QMessageBox::Yes:
225 QList<QListWidgetItem*> found_items =
ui_->list_states->selectedItems();
226 for (QListWidgetItem* found_item : found_items)
228 const std::string&
name = found_item->text().toStdString();
234 catch (std::exception& ex)
236 RCLCPP_ERROR(logger_,
"%s", ex.what());
243 populateRobotStatesList();
246void MotionPlanningFrame::clearStatesButtonClicked()
249 msg_box.setText(
"Clear all stored robot states (from memory, not from the database)?");
250 msg_box.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
251 msg_box.setDefaultButton(QMessageBox::Yes);
252 int ret = msg_box.exec();
255 case QMessageBox::Yes:
258 populateRobotStatesList();
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setQueryGoalState(const moveit::core::RobotState &goal)
void setQueryStartState(const moveit::core::RobotState &start)
moveit::core::RobotStateConstPtr getQueryStartState() const
moveit::core::RobotStateConstPtr getQueryGoalState() const
std::pair< std::string, moveit_msgs::msg::RobotState > RobotStatePair
Ui::MotionPlanningUI * ui_
RobotStateMap robot_states_
MotionPlanningDisplay * planning_display_
moveit_warehouse::RobotStateStoragePtr robot_state_storage_
const moveit::core::RobotModelConstPtr & getRobotModel() const
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotState >::ConstPtr RobotStateWithMetadata
std::string append(const std::string &left, const std::string &right)