44 #include <std_srvs/Empty.h> 45 #include <moveit_msgs/RobotState.h> 47 #include "ui_motion_planning_rviz_plugin_frame.h" 59 ui_->execute_button->setEnabled(
false);
66 ui_->plan_and_execute_button->setEnabled(
false);
67 ui_->execute_button->setEnabled(
false);
74 ui_->stop_button->setEnabled(
false);
96 std::string c =
ui_->path_constraints_combo_box->itemText(index).toStdString();
117 ui_->result_label->setText(
"Planning...");
123 ui_->execute_button->setEnabled(
true);
126 ui_->result_label->setText(QString(
"Time: ").
append(QString::number(
current_plan_->planning_time_,
'f', 3)));
133 ui_->result_label->setText(
"Failed");
142 ui_->stop_button->setEnabled(
true);
156 ui_->stop_button->setEnabled(
true);
157 bool success =
move_group_->move() == moveit::planning_interface::MoveItErrorCode::SUCCESS;
159 ui_->plan_and_execute_button->setEnabled(
true);
172 ui_->result_label->setText(
"Executed");
174 ui_->result_label->setText(!
ui_->stop_button->isEnabled() ?
"Stopped" :
"Failed");
176 ui_->stop_button->setEnabled(
false);
179 if (
ui_->start_state_selection->currentText() ==
"<current>")
187 "update start state");
201 "update goal state");
216 if (
const robot_model::JointModelGroup* jmg =
218 state.setToRandomPositions(jmg);
222 if (v ==
"<random valid>")
226 if (
const robot_model::JointModelGroup* jmg =
230 static const int MAX_ATTEMPTS = 100;
231 int attempt_count = 0;
232 while (attempt_count < MAX_ATTEMPTS)
235 state.setToRandomPositions(jmg);
246 if (attempt_count >= MAX_ATTEMPTS)
247 ROS_WARN(
"Unable to find a random collision free configuration after %d attempts", MAX_ATTEMPTS);
256 if (v ==
"<current>")
261 state = ps->getCurrentState();
265 if (v ==
"<same as goal>")
271 if (v ==
"<same as start>")
279 state.setToDefaultValues(jmg, v);
285 ui_->planning_algorithm_combo_box->clear();
288 ui_->library_label->setText(QString::fromStdString(desc.name));
289 ui_->library_label->setStyleSheet(
"QLabel { color : green; font: bold }");
291 bool found_group =
false;
295 for (std::size_t i = 0; i < desc.planner_ids.size(); ++i)
296 if (desc.planner_ids[i] == group)
298 else if (desc.planner_ids[i].substr(0, group.length()) == group)
300 if (desc.planner_ids[i].size() > group.length() && desc.planner_ids[i][group.length()] ==
'[')
302 std::string
id = desc.planner_ids[i].substr(group.length());
305 id.resize(
id.length() - 1);
306 ui_->planning_algorithm_combo_box->addItem(QString::fromStdString(
id.substr(1)));
311 if (
ui_->planning_algorithm_combo_box->count() == 0 && !found_group)
312 for (std::size_t i = 0; i < desc.planner_ids.size(); ++i)
313 ui_->planning_algorithm_combo_box->addItem(QString::fromStdString(desc.planner_ids[i]));
314 ui_->planning_algorithm_combo_box->insertItem(0,
"<unspecified>");
317 const std::string& default_planner_config =
move_group_->getDefaultPlannerId(found_group ? group : std::string());
318 int defaultIndex =
ui_->planning_algorithm_combo_box->findText(QString::fromStdString(default_planner_config));
319 if (defaultIndex < 0)
321 ui_->planning_algorithm_combo_box->setCurrentIndex(defaultIndex);
333 ui_->path_constraints_combo_box->clear();
334 ui_->path_constraints_combo_box->addItem(
"None");
335 for (std::size_t i = 0; i < constr.size(); ++i)
336 ui_->path_constraints_combo_box->addItem(QString::fromStdString(constr[i]));
342 mreq.num_planning_attempts =
ui_->planning_attempts->value();
343 mreq.allowed_planning_time =
ui_->planning_time->value();
344 mreq.max_velocity_scaling_factor =
ui_->velocity_scaling_factor->value();
345 mreq.max_acceleration_scaling_factor =
ui_->acceleration_scaling_factor->value();
347 mreq.workspace_parameters.min_corner.x =
ui_->wcenter_x->value() -
ui_->wsize_x->value() / 2.0;
348 mreq.workspace_parameters.min_corner.y =
ui_->wcenter_y->value() -
ui_->wsize_y->value() / 2.0;
349 mreq.workspace_parameters.min_corner.z =
ui_->wcenter_z->value() -
ui_->wsize_z->value() / 2.0;
350 mreq.workspace_parameters.max_corner.x =
ui_->wcenter_x->value() +
ui_->wsize_x->value() / 2.0;
351 mreq.workspace_parameters.max_corner.y =
ui_->wcenter_y->value() +
ui_->wsize_y->value() / 2.0;
352 mreq.workspace_parameters.max_corner.z =
ui_->wcenter_z->value() +
ui_->wsize_z->value() / 2.0;
354 const robot_state::JointModelGroup* jmg = s->getJointModelGroup(mreq.group_name);
357 mreq.goal_constraints.resize(1);
364 robot_model::VariableBounds bx, by, bz;
365 bx.position_bounded_ = by.position_bounded_ = bz.position_bounded_ =
true;
367 robot_model::JointModel::Bounds b(3);
368 bx.min_position_ =
ui_->wcenter_x->value() -
ui_->wsize_x->value() / 2.0;
369 bx.max_position_ =
ui_->wcenter_x->value() +
ui_->wsize_x->value() / 2.0;
370 by.min_position_ =
ui_->wcenter_y->value() -
ui_->wsize_y->value() / 2.0;
371 by.max_position_ =
ui_->wcenter_y->value() +
ui_->wsize_y->value() / 2.0;
372 bz.min_position_ =
ui_->wcenter_z->value() -
ui_->wsize_z->value() / 2.0;
373 bz.max_position_ =
ui_->wcenter_z->value() +
ui_->wsize_z->value() / 2.0;
376 move_group_->setWorkspace(bx.min_position_, by.min_position_, bz.min_position_, bx.max_position_, by.max_position_,
380 if (psm && psm->getRobotModelLoader() && psm->getRobotModelLoader()->getModel())
382 const robot_model::RobotModelPtr& kmodel = psm->getRobotModelLoader()->getModel();
383 const std::vector<robot_model::JointModel*>& jm = kmodel->getJointModels();
384 for (std::size_t i = 0; i < jm.size(); ++i)
385 if (jm[i]->getType() == robot_model::JointModel::PLANAR)
387 jm[i]->setVariableBounds(jm[i]->
getName() +
"/" + jm[i]->getLocalVariableNames()[0], bx);
388 jm[i]->setVariableBounds(jm[i]->
getName() +
"/" + jm[i]->getLocalVariableNames()[1], by);
390 else if (jm[i]->getType() == robot_model::JointModel::FLOATING)
392 jm[i]->setVariableBounds(jm[i]->
getName() +
"/" + jm[i]->getLocalVariableNames()[0], bx);
393 jm[i]->setVariableBounds(jm[i]->
getName() +
"/" + jm[i]->getLocalVariableNames()[1], by);
394 jm[i]->setVariableBounds(jm[i]->
getName() +
"/" + jm[i]->getLocalVariableNames()[2], bz);
404 move_group_->setNumPlanningAttempts(
ui_->planning_attempts->value());
405 move_group_->setMaxVelocityScalingFactor(
ui_->velocity_scaling_factor->value());
406 move_group_->setMaxAccelerationScalingFactor(
ui_->acceleration_scaling_factor->value());
435 robot_state::RobotState state = ps->getCurrentState();
449 robot_state::RobotState state = ps->getCurrentState();
457 moveit_msgs::RobotState msg_no_attached(*msg);
458 msg_no_attached.attached_collision_objects.clear();
459 msg_no_attached.is_diff =
true;
466 robot_state::RobotStatePtr state(
new robot_state::RobotState(ps->getCurrentState()));
467 robot_state::robotStateMsgToRobotState(ps->getTransforms(), msg_no_attached, *state);
475 moveit_msgs::RobotState msg_no_attached(*msg);
476 msg_no_attached.attached_collision_objects.clear();
477 msg_no_attached.is_diff =
true;
484 robot_state::RobotStatePtr state(
new robot_state::RobotState(ps->getCurrentState()));
485 robot_state::robotStateMsgToRobotState(ps->getTransforms(), msg_no_attached, *state);
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor()
void populatePlannersList(const moveit_msgs::PlannerInterfaceDescription &desc)
void computeExecuteButtonClicked()
void remoteUpdateGoalStateCallback(const std_msgs::EmptyConstPtr &msg)
void remoteUpdateCustomStartStateCallback(const moveit_msgs::RobotStateConstPtr &msg)
moveit::planning_interface::MoveGroupInterface::PlanPtr current_plan_
void populateConstraintsList()
void remoteUpdateStartStateCallback(const std_msgs::EmptyConstPtr &msg)
void executeButtonClicked()
void onFinishedExecution(bool success)
void computePlanAndExecuteButtonClicked()
std::size_t size(custom_string const &s)
bool call(MReq &req, MRes &res)
std::string getName(void *handle)
robot_state::RobotStateConstPtr getQueryStartState() const
void constructPlanningRequest(moveit_msgs::MotionPlanRequest &mreq)
void planAndExecuteButtonClicked()
void setQueryStartState(const robot_state::RobotState &start)
ros::ServiceClient clear_octomap_service_client_
void configureForPlanning()
void configureWorkspace()
void updateQueryStateHelper(robot_state::RobotState &state, const std::string &v)
void setQueryGoalState(const robot_state::RobotState &goal)
void remoteExecuteCallback(const std_msgs::EmptyConstPtr &msg)
void dropVisualizedTrajectory()
void onClearOctomapClicked()
void computePlanButtonClicked()
moveit::planning_interface::MoveGroupInterfacePtr move_group_
void addBackgroundJob(const boost::function< void()> &job, const std::string &name)
moveit_msgs::Constraints constructGoalConstraints(const robot_state::RobotState &state, const robot_model::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
void useStartStateButtonClicked()
std::string getCurrentPlanningGroup() const
void remotePlanCallback(const std_msgs::EmptyConstPtr &msg)
void pathConstraintsIndexChanged(int index)
void computeStopButtonClicked()
#define ROS_WARN_STREAM(args)
bool waitForCurrentRobotState(const ros::Time &t=ros::Time::now())
wait for robot state more recent than t
robot_state::RobotStateConstPtr getQueryGoalState() const
MotionPlanningDisplay * planning_display_
Ui::MotionPlanningUI * ui_
void addMainLoopJob(const boost::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called ...
void useGoalStateButtonClicked()
void remoteUpdateCustomGoalStateCallback(const moveit_msgs::RobotStateConstPtr &msg)
void allowLookingToggled(bool checked)
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
void useStartStateButtonExec()
void useGoalStateButtonExec()
void remoteStopCallback(const std_msgs::EmptyConstPtr &msg)
void allowReplanningToggled(bool checked)
void spawnBackgroundJob(const boost::function< void()> &job)
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene