42 #include <object_recognition_msgs/action/object_recognition.hpp>
44 #include <tf2_eigen/tf2_eigen.hpp>
46 #include "ui_motion_planning_rviz_plugin_frame.h"
50 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros_visualization.motion_planning_frame_manipulation");
53 void MotionPlanningFrame::detectObjectsButtonClicked()
71 void MotionPlanningFrame::processDetectedObjects()
73 pick_object_name_.clear();
75 std::vector<std::string> object_ids;
76 double min_x =
ui_->roi_center_x->value() -
ui_->roi_size_x->value() / 2.0;
77 double min_y =
ui_->roi_center_y->value() -
ui_->roi_size_y->value() / 2.0;
78 double min_z =
ui_->roi_center_z->value() -
ui_->roi_size_z->value() / 2.0;
80 double max_x =
ui_->roi_center_x->value() +
ui_->roi_size_x->value() / 2.0;
81 double max_y =
ui_->roi_center_y->value() +
ui_->roi_size_y->value() / 2.0;
82 double max_z =
ui_->roi_center_z->value() +
ui_->roi_size_z->value() / 2.0;
84 rclcpp::Time start_time = rclcpp::Clock().now();
85 while (object_ids.empty() && (rclcpp::Clock().now() - start_time) <= rclcpp::Duration::from_seconds(3))
90 const collision_detection::WorldConstPtr& world = ps->getWorld();
92 for (
const auto&
object : *world)
94 const auto& position =
object.second->pose_.translation();
95 if (position.x() >= min_x && position.x() <= max_x && position.y() >= min_y && position.y() <= max_y &&
96 position.z() >= min_z && position.z() <= max_z)
98 object_ids.push_back(
object.first);
101 if (!object_ids.empty())
104 rclcpp::sleep_for(std::chrono::milliseconds(500));
107 RCLCPP_DEBUG(LOGGER,
"Found %d objects",
static_cast<int>(object_ids.size()));
108 updateDetectedObjectsList(object_ids);
111 void MotionPlanningFrame::selectedDetectedObjectChanged()
113 QList<QListWidgetItem*> sel =
ui_->detected_objects_list->selectedItems();
116 RCLCPP_INFO(LOGGER,
"No objects to select");
120 std_msgs::msg::ColorRGBA pick_object_color;
121 pick_object_color.r = 1.0;
122 pick_object_color.g = 0.0;
123 pick_object_color.b = 0.0;
124 pick_object_color.a = 1.0;
128 if (!selected_object_name_.empty())
129 ps->removeObjectColor(selected_object_name_);
130 selected_object_name_ = sel[0]->text().toStdString();
131 ps->setObjectColor(selected_object_name_, pick_object_color);
135 void MotionPlanningFrame::detectedObjectChanged(QListWidgetItem* )
139 void MotionPlanningFrame::triggerObjectDetection()
141 if (!object_recognition_client_)
143 object_recognition_client_ = rclcpp_action::create_client<object_recognition_msgs::action::ObjectRecognition>(
145 if (!object_recognition_client_->wait_for_action_server(std::chrono::seconds(3)))
147 RCLCPP_ERROR(LOGGER,
"Object recognition action server not responsive");
152 object_recognition_msgs::action::ObjectRecognition::Goal goal;
153 auto goal_handle_future = object_recognition_client_->async_send_goal(goal);
154 goal_handle_future.wait();
155 if (goal_handle_future.get()->get_status() != rclcpp_action::GoalStatus::STATUS_SUCCEEDED)
157 RCLCPP_ERROR(LOGGER,
"ObjectRecognition client: send goal call failed");
162 void MotionPlanningFrame::listenDetectedObjects(
163 const object_recognition_msgs::msg::RecognizedObjectArray::ConstSharedPtr& )
165 rclcpp::sleep_for(std::chrono::seconds(1));
169 void MotionPlanningFrame::updateDetectedObjectsList(
const std::vector<std::string>& object_ids)
171 ui_->detected_objects_list->setUpdatesEnabled(
false);
172 bool old_state =
ui_->detected_objects_list->blockSignals(
true);
173 ui_->detected_objects_list->clear();
175 for (std::size_t i = 0; i < object_ids.size(); ++i)
177 QListWidgetItem* item =
178 new QListWidgetItem(QString::fromStdString(object_ids[i]),
ui_->detected_objects_list,
static_cast<int>(i));
179 item->setToolTip(item->text());
180 Qt::ItemFlags flags = item->flags();
181 flags &= ~(Qt::ItemIsUserCheckable);
182 item->setFlags(flags);
183 ui_->detected_objects_list->addItem(item);
186 ui_->detected_objects_list->blockSignals(old_state);
187 ui_->detected_objects_list->setUpdatesEnabled(
true);
188 if (!object_ids.empty())
189 ui_->pick_button->setEnabled(
true);
193 void MotionPlanningFrame::updateTables()
195 RCLCPP_DEBUG(LOGGER,
"Update table callback");
199 void MotionPlanningFrame::publishTables()
207 void MotionPlanningFrame::selectedSupportSurfaceChanged()
209 QList<QListWidgetItem*> sel =
ui_->support_surfaces_list->selectedItems();
212 RCLCPP_INFO(LOGGER,
"No tables to select");
216 std_msgs::msg::ColorRGBA selected_support_surface_color;
217 selected_support_surface_color.r = 0.0;
218 selected_support_surface_color.g = 0.0;
219 selected_support_surface_color.b = 1.0;
220 selected_support_surface_color.a = 1.0;
224 if (!selected_support_surface_name_.empty())
225 ps->removeObjectColor(selected_support_surface_name_);
226 selected_support_surface_name_ = sel[0]->text().toStdString();
227 ps->setObjectColor(selected_support_surface_name_, selected_support_surface_color);
231 void MotionPlanningFrame::updateSupportSurfacesList()
243 std::vector<std::string> support_ids;
244 RCLCPP_INFO(LOGGER,
"%d Tables in collision world",
static_cast<int>(support_ids.size()));
246 ui_->support_surfaces_list->setUpdatesEnabled(
false);
247 bool old_state =
ui_->support_surfaces_list->blockSignals(
true);
248 ui_->support_surfaces_list->clear();
250 for (std::size_t i = 0; i < support_ids.size(); ++i)
252 QListWidgetItem* item =
253 new QListWidgetItem(QString::fromStdString(support_ids[i]),
ui_->support_surfaces_list,
static_cast<int>(i));
254 item->setToolTip(item->text());
255 Qt::ItemFlags flags = item->flags();
256 flags &= ~(Qt::ItemIsUserCheckable);
257 item->setFlags(flags);
258 ui_->support_surfaces_list->addItem(item);
261 ui_->support_surfaces_list->blockSignals(old_state);
262 ui_->support_surfaces_list->setUpdatesEnabled(
true);
266 void MotionPlanningFrame::pickObjectButtonClicked()
268 RCLCPP_WARN_STREAM(LOGGER,
"Pick & Place capability isn't supported yet");
305 void MotionPlanningFrame::placeObjectButtonClicked()
307 QList<QListWidgetItem*> sel_table =
ui_->support_surfaces_list->selectedItems();
310 if (!sel_table.empty())
311 support_surface_name_ = sel_table[0]->text().toStdString();
314 support_surface_name_.clear();
315 RCLCPP_ERROR(LOGGER,
"Need to specify table to place object on");
319 ui_->pick_button->setEnabled(
false);
320 ui_->place_button->setEnabled(
false);
322 std::vector<const moveit::core::AttachedBody*> attached_bodies;
326 RCLCPP_ERROR(LOGGER,
"No planning scene");
331 ps->getCurrentState().getAttachedBodies(attached_bodies, jmg);
333 if (attached_bodies.empty())
335 RCLCPP_ERROR(LOGGER,
"No bodies to place");
339 geometry_msgs::msg::Quaternion upright_orientation;
340 upright_orientation.w = 1.0;
343 place_poses_.clear();
std::string getCurrentPlanningGroup() const
Ui::MotionPlanningUI * ui_
MotionPlanningDisplay * planning_display_
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene
planning_scene_monitor::LockedPlanningSceneRW getPlanningSceneRW()
get write access to planning scene
void addMainLoopJob(const std::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called
void addBackgroundJob(const std::function< void()> &job, const std::string &name)
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
const std::string OBJECT_RECOGNITION_ACTION
const rclcpp::Logger LOGGER