39 #include <rviz_common/properties/int_property.hpp> 
   40 #include <rviz_common/properties/float_property.hpp> 
   41 #include <rviz_common/properties/string_property.hpp> 
   47 static const rclcpp::Logger 
LOGGER = rclcpp::get_logger(
"moveit_ros_visualization.motion_planning_param_widget");
 
   50   : 
rviz_common::properties::PropertyTreeWidget(parent)
 
   52   property_tree_model_ = 
nullptr;
 
   57   delete property_tree_model_;
 
   69   group_name_ = group_name;
 
   70   this->setModel(
nullptr);
 
   71   if (property_tree_model_)
 
   72     delete property_tree_model_;
 
   73   property_tree_model_ = 
nullptr;
 
   79   lvalue = value.toLong(&ok);
 
   86   dvalue = value.toDouble(&ok);
 
   90 rviz_common::properties::Property* MotionPlanningParamWidget::createPropertyTree()
 
   92   if (planner_id_.empty())
 
   94   const std::map<std::string, std::string>& params = move_group_->getPlannerParams(planner_id_, group_name_);
 
   96   auto root = 
new rviz_common::properties::Property(QString::fromStdString(planner_id_ + 
" parameters"));
 
   97   for (
const std::pair<const std::string, std::string>& param : params)
 
   99     const QString key = QString::fromStdString(param.first);
 
  100     const QString value = QString::fromStdString(param.second);
 
  106       new rviz_common::properties::IntProperty(key, value_long, QString(), root, SLOT(changedValue()), 
this);
 
  110       new rviz_common::properties::FloatProperty(key, value_double, QString(), root, SLOT(changedValue()), 
this);
 
  113       new rviz_common::properties::StringProperty(key, value, QString(), root, SLOT(changedValue()), 
this);
 
  118 void MotionPlanningParamWidget::changedValue()
 
  122   rviz_common::properties::Property* source = qobject_cast<rviz_common::properties::Property*>(QObject::sender());
 
  123   std::map<std::string, std::string> params;
 
  124   params[source->getName().toStdString()] = source->getValue().toString().toStdString();
 
  125   move_group_->setPlannerParams(planner_id_, group_name_, params);
 
  130   planner_id_ = planner_id;
 
  134   rviz_common::properties::PropertyTreeModel* old_model = property_tree_model_;
 
  135   rviz_common::properties::Property* root = createPropertyTree();
 
  136   property_tree_model_ = root ? 
new rviz_common::properties::PropertyTreeModel(root) : 
nullptr;
 
  137   this->setModel(property_tree_model_);
 
Simple interface to MoveIt components.
 
bool try_lexical_convert(const QString &value, long &lvalue)
 
const rclcpp::Logger LOGGER