@@ -96,6 +96,11 @@ void BasePlacementWidget::showUreachModels()
96
96
Q_EMIT SendShowUmodel (show_umodels_);
97
97
}
98
98
99
+ void BasePlacementWidget::getSelectedGroup (std::string group_name)
100
+ {
101
+ group_name_ = group_name;
102
+ }
103
+
99
104
100
105
void BasePlacementWidget::showUnionMapFromUI ()
101
106
{
@@ -134,25 +139,25 @@ void BasePlacementWidget::getBasePlacePlanMethod(std::vector< std::string > meth
134
139
135
140
void BasePlacementWidget::selectedMethod (int index)
136
141
{
142
+ Q_EMIT SendSelectedMethod (index );
137
143
if (index ==4 )
138
144
{
139
- ROS_INFO (" AHA.The user intuition method is selected. Let's Play" );
140
- add_robot = new AddRobotBase ();
141
-
142
- // add_robot to widget
143
- connect (this , SIGNAL (parseWayPointBtn_signal ()), add_robot, SLOT (parseWayPoints ()));
144
- connect (add_robot, SIGNAL (baseWayPoints_signal (std::vector<geometry_msgs::Pose>)), this , SLOT (getWaypoints (std::vector<geometry_msgs::Pose>)));
145
- connect (this , SIGNAL (clearAllPoints_signal ()), add_robot, SLOT (clearAllPointsRviz ()));
145
+ if (group_name_.size ()>0 )
146
+ {
147
+ add_robot = new AddRobotBase (0 , group_name_);
148
+ ROS_INFO (" AHA.The user intuition method is selected. Let's Play" );
149
+ // add_robot to widget
150
+ connect (this , SIGNAL (parseWayPointBtn_signal ()), add_robot, SLOT (parseWayPoints ()));
151
+ connect (add_robot, SIGNAL (baseWayPoints_signal (std::vector<geometry_msgs::Pose>)), this , SLOT (getWaypoints (std::vector<geometry_msgs::Pose>)));
152
+ connect (this , SIGNAL (clearAllPoints_signal ()), add_robot, SLOT (clearAllPointsRviz ()));
153
+ }
146
154
}
147
155
else
148
156
{
149
157
if (!add_robot == 0 )
150
158
delete add_robot;
151
159
add_robot = 0 ;
152
160
}
153
-
154
-
155
- Q_EMIT SendSelectedMethod (index );
156
161
}
157
162
158
163
void BasePlacementWidget::getWaypoints (std::vector<geometry_msgs::Pose> base_poses)
0 commit comments