42 #include <QMessageBox> 
   43 #include <QInputDialog> 
   45 #include "ui_motion_planning_rviz_plugin_frame.h" 
   49 static const rclcpp::Logger 
LOGGER = rclcpp::get_logger(
"moveit_ros_visualization.motion_planning_frame_states");
 
   51 void MotionPlanningFrame::populateRobotStatesList()
 
   53   ui_->list_states->clear();
 
   54   for (std::pair<const std::string, moveit_msgs::msg::RobotState>& robot_state : 
robot_states_)
 
   56     QListWidgetItem* item = 
new QListWidgetItem(QString(robot_state.first.c_str()));
 
   57     ui_->list_states->addItem(item);
 
   61 void MotionPlanningFrame::loadStateButtonClicked()
 
   68         QInputDialog::getText(
this, tr(
"Robot states to load"), tr(
"Pattern:"), QLineEdit::Normal, 
".*", &ok);
 
   69     if (ok && !
text.isEmpty())
 
   71       loadStoredStates(
text.toStdString());
 
   76     QMessageBox::warning(
this, 
"Warning", 
"Not connected to a database.");
 
   80 void MotionPlanningFrame::loadStoredStates(
const std::string& pattern)
 
   82   std::vector<std::string> names;
 
   87   catch (std::exception& ex)
 
   89     QMessageBox::warning(
this, 
"Cannot query the database",
 
   90                          QString(
"Wrongly formatted regular expression for robot states: ").
append(ex.what()));
 
   94   clearStatesButtonClicked();
 
   96   for (
const std::string& 
name : names)
 
   99     bool got_state = 
false;
 
  104     catch (std::exception& ex)
 
  106       RCLCPP_ERROR(LOGGER, 
"%s", ex.what());
 
  120   populateRobotStatesList();
 
  127   std::stringstream ss;
 
  131   QString 
text = QInputDialog::getText(
this, tr(
"Choose a name"), tr(
"State name:"), QLineEdit::Normal,
 
  132                                        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."));
 
  146         moveit_msgs::msg::RobotState msg;
 
  157           catch (std::exception& ex)
 
  159             RCLCPP_ERROR(LOGGER, 
"Cannot save robot state on the database: %s", ex.what());
 
  164           QMessageBox::warning(
this, 
"Warning", 
"Not connected to a database. The state will be created but not stored");
 
  169       QMessageBox::warning(
this, 
"Start state not saved", 
"Cannot use an empty name for a new start state.");
 
  171   populateRobotStatesList();
 
  174 void MotionPlanningFrame::saveStartStateButtonClicked()
 
  179 void MotionPlanningFrame::saveGoalStateButtonClicked()
 
  184 void MotionPlanningFrame::setAsStartStateButtonClicked()
 
  186   QListWidgetItem* item = 
ui_->list_states->currentItem();
 
  196 void MotionPlanningFrame::setAsGoalStateButtonClicked()
 
  198   QListWidgetItem* item = 
ui_->list_states->currentItem();
 
  208 void MotionPlanningFrame::removeStateButtonClicked()
 
  214     msg_box.setText(
"All the selected states will be removed from the database");
 
  215     msg_box.setInformativeText(
"Do you want to continue?");
 
  216     msg_box.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
 
  217     msg_box.setDefaultButton(QMessageBox::No);
 
  218     int ret = msg_box.exec();
 
  222       case QMessageBox::Yes:
 
  224         QList<QListWidgetItem*> found_items = 
ui_->list_states->selectedItems();
 
  225         for (QListWidgetItem* found_item : found_items)
 
  227           const std::string& 
name = found_item->text().toStdString();
 
  233           catch (std::exception& ex)
 
  235             RCLCPP_ERROR(LOGGER, 
"%s", ex.what());
 
  242   populateRobotStatesList();
 
  245 void MotionPlanningFrame::clearStatesButtonClicked()
 
  248   msg_box.setText(
"Clear all stored robot states (from memory, not from the database)?");
 
  249   msg_box.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
 
  250   msg_box.setDefaultButton(QMessageBox::Yes);
 
  251   int ret = msg_box.exec();
 
  254     case QMessageBox::Yes:
 
  257       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)
 
const rclcpp::Logger LOGGER