motion_planning_param_widget.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Robert Haschke */
36 
42 
44 
45 namespace moveit_rviz_plugin
46 {
47 MotionPlanningParamWidget::MotionPlanningParamWidget(QWidget* parent) : rviz::PropertyTreeWidget(parent)
48 {
49  property_tree_model_ = nullptr;
50 }
51 
53 {
54  delete property_tree_model_;
55 }
56 
57 void MotionPlanningParamWidget::setMoveGroup(const mpi::MoveGroupInterfacePtr& mg)
58 {
59  move_group_ = mg;
60  if (mg)
62 }
63 
64 void MotionPlanningParamWidget::setGroupName(const std::string& group_name)
65 {
66  group_name_ = group_name;
67  this->setModel(nullptr);
69  delete property_tree_model_;
70  property_tree_model_ = nullptr;
71 }
72 
73 bool try_lexical_convert(const QString& value, long& lvalue)
74 {
75  bool ok;
76  lvalue = value.toLong(&ok);
77  return ok;
78 }
79 
80 bool try_lexical_convert(const QString& value, double& dvalue)
81 {
82  bool ok;
83  dvalue = value.toDouble(&ok);
84  return ok;
85 }
86 
88 {
89  if (planner_id_.empty())
90  return nullptr;
91  const std::map<std::string, std::string>& params = move_group_->getPlannerParams(planner_id_, group_name_);
92 
93  rviz::Property* root = new rviz::Property(QString::fromStdString(planner_id_ + " parameters"));
94  for (const std::pair<const std::string, std::string>& param : params)
95  {
96  const QString key = QString::fromStdString(param.first);
97  const QString value = QString::fromStdString(param.second);
98  long value_long;
99  double value_double;
100 
101  if (try_lexical_convert(value, value_long))
102  {
103  new rviz::IntProperty(key, value_long, QString(), root, SLOT(changedValue()), this);
104  }
105  else if (try_lexical_convert(value, value_double))
106  {
107  new rviz::FloatProperty(key, value_double, QString(), root, SLOT(changedValue()), this);
108  }
109  else
110  new rviz::StringProperty(key, value, QString(), root, SLOT(changedValue()), this);
111  }
112  return root;
113 }
114 
116 {
117  if (!move_group_)
118  return;
119  rviz::Property* source = qobject_cast<rviz::Property*>(QObject::sender());
120  std::map<std::string, std::string> params;
121  params[source->getName().toStdString()] = source->getValue().toString().toStdString();
122  move_group_->setPlannerParams(planner_id_, group_name_, params);
123 }
124 
125 void MotionPlanningParamWidget::setPlannerId(const std::string& planner_id)
126 {
127  planner_id_ = planner_id;
128  if (!move_group_)
129  return;
130 
133  property_tree_model_ = root ? new rviz::PropertyTreeModel(root) : nullptr;
135  if (old_model)
136  delete old_model;
137 }
138 } // namespace moveit_rviz_plugin
motion_planning_param_widget.h
rviz::PropertyTreeModel
moveit_rviz_plugin::MotionPlanningParamWidget::setMoveGroup
void setMoveGroup(const moveit::planning_interface::MoveGroupInterfacePtr &mg)
Definition: motion_planning_param_widget.cpp:89
int_property.h
moveit_rviz_plugin::MotionPlanningParamWidget::property_tree_model_
rviz::PropertyTreeModel * property_tree_model_
Definition: motion_planning_param_widget.h:73
moveit_rviz_plugin::MotionPlanningParamWidget::planner_id_
std::string planner_id_
Definition: motion_planning_param_widget.h:77
moveit_rviz_plugin::MotionPlanningParamWidget::group_name_
std::string group_name_
Definition: motion_planning_param_widget.h:76
rviz::Property::getValue
virtual QVariant getValue() const
ok
ROSCPP_DECL bool ok()
float_property.h
moveit_rviz_plugin::MotionPlanningParamWidget::createPropertyTree
rviz::Property * createPropertyTree()
Definition: motion_planning_param_widget.cpp:119
moveit_rviz_plugin::try_lexical_convert
bool try_lexical_convert(const QString &value, long &lvalue)
Definition: motion_planning_param_widget.cpp:105
rviz::FloatProperty
rviz::Property
moveit_rviz_plugin::MotionPlanningParamWidget::~MotionPlanningParamWidget
~MotionPlanningParamWidget() override
Definition: motion_planning_param_widget.cpp:84
moveit_rviz_plugin::MotionPlanningParamWidget::MotionPlanningParamWidget
MotionPlanningParamWidget(const MotionPlanningParamWidget &)=delete
moveit_rviz_plugin::MotionPlanningParamWidget::move_group_
moveit::planning_interface::MoveGroupInterfacePtr move_group_
Definition: motion_planning_param_widget.h:75
rviz
rviz::StringProperty
rviz::PropertyTreeWidget::setModel
void setModel(PropertyTreeModel *model)
value
float value
moveit_rviz_plugin::MotionPlanningParamWidget::setPlannerId
void setPlannerId(const std::string &planner_id)
Definition: motion_planning_param_widget.cpp:157
move_group_interface.h
moveit_rviz_plugin
Definition: motion_planning_display.h:80
rviz::Property::getName
virtual QString getName() const
moveit_rviz_plugin::MotionPlanningParamWidget::setGroupName
void setGroupName(const std::string &group_name)
Definition: motion_planning_param_widget.cpp:96
moveit_rviz_plugin::MotionPlanningParamWidget::changedValue
void changedValue()
Definition: motion_planning_param_widget.cpp:147
param
T param(const std::string &param_name, const T &default_val)
moveit::planning_interface
root
root
string_property.h
rviz::IntProperty


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Sat Mar 15 2025 02:27:25