moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
39#include <rviz_common/properties/int_property.hpp>
40#include <rviz_common/properties/float_property.hpp>
41#include <rviz_common/properties/string_property.hpp>
42
44
45namespace moveit_rviz_plugin
46{
47
49 : rviz_common::properties::PropertyTreeWidget(parent)
50{
51 property_tree_model_ = nullptr;
52}
53
55{
56 delete property_tree_model_;
57}
58
59void MotionPlanningParamWidget::setMoveGroup(const mpi::MoveGroupInterfacePtr& mg)
60{
61 move_group_ = mg;
62 if (mg)
63 setPlannerId(planner_id_);
64}
65
66void MotionPlanningParamWidget::setGroupName(const std::string& group_name)
67{
68 group_name_ = group_name;
69 setModel(nullptr);
70 if (property_tree_model_)
71 delete property_tree_model_;
72 property_tree_model_ = nullptr;
73}
74
75bool tryLexicalConvert(const QString& value, long& lvalue)
76{
77 bool ok;
78 lvalue = value.toLong(&ok);
79 return ok;
80}
81
82bool tryLexicalConvert(const QString& value, double& dvalue)
83{
84 bool ok;
85 dvalue = value.toDouble(&ok);
86 return ok;
87}
88
89rviz_common::properties::Property* MotionPlanningParamWidget::createPropertyTree()
90{
91 if (planner_id_.empty())
92 return nullptr;
93 const std::map<std::string, std::string>& params = move_group_->getPlannerParams(planner_id_, group_name_);
94
95 auto root = new rviz_common::properties::Property(QString::fromStdString(planner_id_ + " parameters"));
96 for (const std::pair<const std::string, std::string>& param : params)
97 {
98 const QString key = QString::fromStdString(param.first);
99 const QString value = QString::fromStdString(param.second);
100 long value_long;
101 double value_double;
102
103 if (tryLexicalConvert(value, value_long))
104 {
105 new rviz_common::properties::IntProperty(key, value_long, QString(), root, SLOT(changedValue()), this);
106 }
107 else if (tryLexicalConvert(value, value_double))
108 {
109 new rviz_common::properties::FloatProperty(key, value_double, QString(), root, SLOT(changedValue()), this);
110 }
111 else
112 new rviz_common::properties::StringProperty(key, value, QString(), root, SLOT(changedValue()), this);
113 }
114 return root;
115}
116
117void MotionPlanningParamWidget::changedValue()
118{
119 if (!move_group_)
120 return;
121 rviz_common::properties::Property* source = qobject_cast<rviz_common::properties::Property*>(QObject::sender());
122 std::map<std::string, std::string> params;
123 params[source->getName().toStdString()] = source->getValue().toString().toStdString();
124 move_group_->setPlannerParams(planner_id_, group_name_, params);
125}
126
127void MotionPlanningParamWidget::setPlannerId(const std::string& planner_id)
128{
129 planner_id_ = planner_id;
130 if (!move_group_)
131 return;
132
133 rviz_common::properties::PropertyTreeModel* old_model = property_tree_model_;
134 rviz_common::properties::Property* root = createPropertyTree();
135 property_tree_model_ = root ? new rviz_common::properties::PropertyTreeModel(root) : nullptr;
136 setModel(property_tree_model_);
137 if (old_model)
138 delete old_model;
139}
140} // namespace moveit_rviz_plugin
void setMoveGroup(const moveit::planning_interface::MoveGroupInterfacePtr &mg)
MotionPlanningParamWidget(const MotionPlanningParamWidget &)=delete
Simple interface to MoveIt components.
bool tryLexicalConvert(const QString &value, long &lvalue)