Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h>
00038 #include <moveit/move_group_interface/move_group.h>
00039 #include <rviz/properties/int_property.h>
00040 #include <rviz/properties/float_property.h>
00041 #include <rviz/properties/string_property.h>
00042
00043 namespace mpi = moveit::planning_interface;
00044
00045 namespace moveit_rviz_plugin
00046 {
00047 MotionPlanningParamWidget::MotionPlanningParamWidget(QWidget* parent) : rviz::PropertyTreeWidget(parent)
00048 {
00049 property_tree_model_ = NULL;
00050 }
00051
00052 MotionPlanningParamWidget::~MotionPlanningParamWidget()
00053 {
00054 }
00055
00056 void MotionPlanningParamWidget::setMoveGroup(const mpi::MoveGroupPtr& mg)
00057 {
00058 move_group_ = mg;
00059 if (mg)
00060 setPlannerId(planner_id_);
00061 }
00062
00063 void MotionPlanningParamWidget::setGroupName(const std::string& group_name)
00064 {
00065 group_name_ = group_name;
00066 this->setModel(NULL);
00067 if (property_tree_model_)
00068 delete property_tree_model_;
00069 property_tree_model_ = NULL;
00070 }
00071
00072 bool try_lexical_convert(const QString& value, long& lvalue)
00073 {
00074 bool ok;
00075 lvalue = value.toLong(&ok);
00076 return ok;
00077 }
00078
00079 bool try_lexical_convert(const QString& value, double& dvalue)
00080 {
00081 bool ok;
00082 dvalue = value.toDouble(&ok);
00083 return ok;
00084 }
00085
00086 rviz::Property* MotionPlanningParamWidget::createPropertyTree()
00087 {
00088 if (planner_id_.empty())
00089 return NULL;
00090 const std::map<std::string, std::string>& params = move_group_->getPlannerParams(planner_id_, group_name_);
00091
00092 rviz::Property* root = new rviz::Property(QString::fromStdString(planner_id_ + " parameters"));
00093 for (std::map<std::string, std::string>::const_iterator it = params.begin(), end = params.end(); it != end; ++it)
00094 {
00095 const QString key = QString::fromStdString(it->first);
00096 const QString value = QString::fromStdString(it->second);
00097 long value_long;
00098 double value_double;
00099
00100 if (try_lexical_convert(value, value_long))
00101 {
00102 new rviz::IntProperty(key, value_long, QString(), root, SLOT(changedValue()), this);
00103 }
00104 else if (try_lexical_convert(value, value_double))
00105 {
00106 new rviz::FloatProperty(key, value_double, QString(), root, SLOT(changedValue()), this);
00107 }
00108 else
00109 new rviz::StringProperty(key, value, QString(), root, SLOT(changedValue()), this);
00110 }
00111 return root;
00112 }
00113
00114 void MotionPlanningParamWidget::changedValue()
00115 {
00116 if (!move_group_)
00117 return;
00118 rviz::Property* source = qobject_cast<rviz::Property*>(QObject::sender());
00119 std::map<std::string, std::string> params;
00120 params[source->getName().toStdString()] = source->getValue().toString().toStdString();
00121 move_group_->setPlannerParams(planner_id_, group_name_, params);
00122 }
00123
00124 void MotionPlanningParamWidget::setPlannerId(const std::string& planner_id)
00125 {
00126 planner_id_ = planner_id;
00127 if (!move_group_)
00128 return;
00129
00130 rviz::PropertyTreeModel* old_model = property_tree_model_;
00131 rviz::Property* root = createPropertyTree();
00132 property_tree_model_ = root ? new rviz::PropertyTreeModel(root) : NULL;
00133 this->setModel(property_tree_model_);
00134 if (old_model)
00135 delete old_model;
00136 }
00137 }