44 #include <std_srvs/srv/empty.hpp>
45 #include <moveit_msgs/msg/robot_state.hpp>
46 #include <tf2_eigen/tf2_eigen.hpp>
49 #include "ui_motion_planning_rviz_plugin_frame.h"
54 void MotionPlanningFrame::planButtonClicked()
56 publishSceneIfNeeded();
60 void MotionPlanningFrame::executeButtonClicked()
62 ui_->execute_button->setEnabled(
false);
67 void MotionPlanningFrame::planAndExecuteButtonClicked()
69 publishSceneIfNeeded();
70 ui_->plan_and_execute_button->setEnabled(
false);
71 ui_->execute_button->setEnabled(
false);
76 void MotionPlanningFrame::stopButtonClicked()
78 ui_->stop_button->setEnabled(
false);
82 void MotionPlanningFrame::allowReplanningToggled(
bool checked)
88 void MotionPlanningFrame::allowLookingToggled(
bool checked)
94 void MotionPlanningFrame::pathConstraintsIndexChanged(
int index)
100 std::string c =
ui_->path_constraints_combo_box->itemText(index).toStdString();
102 RCLCPP_WARN_STREAM(logger_,
"Unable to set the path constraints: " << c);
109 void MotionPlanningFrame::onClearOctomapClicked()
111 auto req = std::make_shared<std_srvs::srv::Empty::Request>();
112 auto result = clear_octomap_service_client_->async_send_request(req);
114 if (result.wait_for(std::chrono::seconds(0)) != std::future_status::ready)
116 RCLCPP_ERROR(logger_,
"Failed to call clear_octomap_service");
118 ui_->clear_octomap_button->setEnabled(
false);
121 bool MotionPlanningFrame::computeCartesianPlan()
123 rclcpp::Time start = rclcpp::Clock().now();
126 std::vector<geometry_msgs::msg::Pose> waypoints;
127 const std::string& link_name =
move_group_->getEndEffectorLink();
131 RCLCPP_ERROR_STREAM(logger_,
"Failed to determine unique end-effector link: " << link_name);
137 double cart_step_size = 0.01;
138 bool avoid_collisions =
true;
141 moveit_msgs::msg::RobotTrajectory trajectory;
142 double fraction =
move_group_->computeCartesianPath(waypoints, cart_step_size, trajectory, avoid_collisions);
146 RCLCPP_INFO(logger_,
"Achieved %f %% of Cartesian path", fraction * 100.);
151 rt.setRobotTrajectoryMsg(*
move_group_->getCurrentState(), trajectory);
153 bool success = time_parameterization.
computeTimeStamps(rt,
ui_->velocity_scaling_factor->value(),
154 ui_->acceleration_scaling_factor->value());
155 RCLCPP_INFO(logger_,
"Computing time stamps %s", success ?
"SUCCEEDED" :
"FAILED");
158 current_plan_ = std::make_shared<moveit::planning_interface::MoveGroupInterface::Plan>();
160 current_plan_->planning_time = (rclcpp::Clock().now() - start).seconds();
166 bool MotionPlanningFrame::computeJointSpacePlan()
168 current_plan_ = std::make_shared<moveit::planning_interface::MoveGroupInterface::Plan>();
172 void MotionPlanningFrame::computePlanButtonClicked()
178 ui_->result_label->setText(
"Planning...");
180 configureForPlanning();
182 bool success = (
ui_->use_cartesian_path->isEnabled() &&
ui_->use_cartesian_path->checkState()) ?
183 computeCartesianPlan() :
184 computeJointSpacePlan();
188 ui_->execute_button->setEnabled(
true);
189 ui_->result_label->setText(QString(
"Time: ").
append(QString::number(
current_plan_->planning_time,
'f', 3)));
194 ui_->result_label->setText(
"Failed");
199 void MotionPlanningFrame::computeExecuteButtonClicked()
202 moveit::planning_interface::MoveGroupInterfacePtr mgi(
move_group_);
205 ui_->stop_button->setEnabled(
true);
206 bool success = mgi->execute(*
current_plan_) == moveit::core::MoveItErrorCode::SUCCESS;
207 onFinishedExecution(success);
211 void MotionPlanningFrame::computePlanAndExecuteButtonClicked()
214 moveit::planning_interface::MoveGroupInterfacePtr mgi(
move_group_);
217 configureForPlanning();
221 mgi->setStartStateToCurrentState();
222 ui_->stop_button->setEnabled(
true);
223 if (
ui_->use_cartesian_path->isEnabled() &&
ui_->use_cartesian_path->checkState())
225 if (computeCartesianPlan())
226 computeExecuteButtonClicked();
230 bool success = mgi->move() == moveit::core::MoveItErrorCode::SUCCESS;
231 onFinishedExecution(success);
233 ui_->plan_and_execute_button->setEnabled(
true);
236 void MotionPlanningFrame::computeStopButtonClicked()
242 void MotionPlanningFrame::onFinishedExecution(
bool success)
247 ui_->result_label->setText(
"Executed");
251 ui_->result_label->setText(!
ui_->stop_button->isEnabled() ?
"Stopped" :
"Failed");
254 ui_->stop_button->setEnabled(
false);
257 if (
ui_->start_state_combo_box->currentText() ==
"<current>")
258 startStateTextChanged(
ui_->start_state_combo_box->currentText());
262 if (
ui_->goal_state_combo_box->currentText() ==
"<previous>")
263 goalStateTextChanged(
ui_->goal_state_combo_box->currentText());
266 void MotionPlanningFrame::onNewPlanningSceneState()
269 if (
ui_->start_state_combo_box->currentText() ==
"<current>")
274 if (
ui_->goal_state_combo_box->currentText() ==
"<current>")
278 void MotionPlanningFrame::startStateTextChanged(
const QString& start_state)
282 "update start state");
285 void MotionPlanningFrame::startStateTextChangedExec(
const std::string& start_state)
288 updateQueryStateHelper(start, start_state);
292 void MotionPlanningFrame::goalStateTextChanged(
const QString& goal_state)
296 "update goal state");
299 void MotionPlanningFrame::goalStateTextChangedExec(
const std::string& goal_state)
302 updateQueryStateHelper(goal, goal_state);
306 void MotionPlanningFrame::planningGroupTextChanged(
const QString& planning_group)
315 configureWorkspace();
322 if (v ==
"<random valid>")
324 configureWorkspace();
330 static const int MAX_ATTEMPTS = 100;
331 int attempt_count = 0;
332 while (attempt_count < MAX_ATTEMPTS)
346 if (attempt_count >= MAX_ATTEMPTS)
347 RCLCPP_WARN(logger_,
"Unable to find a random collision free configuration after %d attempts", MAX_ATTEMPTS);
356 if (v ==
"<current>")
358 rclcpp::Time t = node_->now();
362 state = ps->getCurrentState();
366 if (v ==
"<same as goal>")
372 if (v ==
"<same as start>")
378 if (v ==
"<previous>")
389 void MotionPlanningFrame::populatePlannersList(
const std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc)
391 ui_->planning_pipeline_combo_box->clear();
394 size_t default_planner_index = 0;
397 QString item_text(d.pipeline_id.c_str());
401 if (item_text.isEmpty())
402 item_text = QString::fromStdString(d.name);
403 default_planner_index =
ui_->planning_pipeline_combo_box->count();
405 ui_->planning_pipeline_combo_box->addItem(item_text);
409 ui_->planning_pipeline_combo_box->setItemData(default_planner_index, font, Qt::FontRole);
413 ui_->planning_pipeline_combo_box->setCurrentIndex(default_planner_index);
416 void MotionPlanningFrame::populatePlannerDescription(
const moveit_msgs::msg::PlannerInterfaceDescription& desc)
419 RCLCPP_DEBUG(logger_,
"Found %zu planners for group '%s' and pipeline '%s'", desc.planner_ids.size(), group.c_str(),
420 desc.pipeline_id.c_str());
421 ui_->planning_algorithm_combo_box->clear();
424 ui_->library_label->setText(QString::fromStdString(desc.name));
425 ui_->library_label->setStyleSheet(
"QLabel { color : green; font: bold }");
427 bool found_group =
false;
431 for (
const std::string& planner_id : desc.planner_ids)
433 RCLCPP_DEBUG(logger_,
"planner id: %s", planner_id.c_str());
434 if (planner_id == group)
438 else if (planner_id.substr(0, group.length()) == group)
440 if (planner_id.size() > group.length() && planner_id[group.length()] ==
'[')
442 std::string
id = planner_id.substr(group.length());
445 id.resize(
id.length() - 1);
446 ui_->planning_algorithm_combo_box->addItem(QString::fromStdString(
id.substr(1)));
452 if (
ui_->planning_algorithm_combo_box->count() == 0 && !found_group)
454 for (
const std::string& planner_id : desc.planner_ids)
455 ui_->planning_algorithm_combo_box->addItem(QString::fromStdString(planner_id));
458 ui_->planning_algorithm_combo_box->insertItem(0,
"<unspecified>");
461 const std::string& default_planner_config =
move_group_->getDefaultPlannerId(found_group ? group : std::string());
462 int default_index =
ui_->planning_algorithm_combo_box->findText(QString::fromStdString(default_planner_config));
463 if (default_index < 0)
465 ui_->planning_algorithm_combo_box->setCurrentIndex(default_index);
469 ui_->planning_algorithm_combo_box->setItemData(default_index, font, Qt::FontRole);
472 void MotionPlanningFrame::populateConstraintsList()
478 void MotionPlanningFrame::populateConstraintsList(
const std::vector<std::string>& constr)
480 ui_->path_constraints_combo_box->clear();
481 ui_->path_constraints_combo_box->addItem(
"None");
482 for (
const std::string& constraint : constr)
483 ui_->path_constraints_combo_box->addItem(QString::fromStdString(constraint));
489 mreq.num_planning_attempts =
ui_->planning_attempts->value();
490 mreq.allowed_planning_time =
ui_->planning_time->value();
491 mreq.max_velocity_scaling_factor =
ui_->velocity_scaling_factor->value();
492 mreq.max_acceleration_scaling_factor =
ui_->acceleration_scaling_factor->value();
494 mreq.workspace_parameters.min_corner.x =
ui_->wcenter_x->value() -
ui_->wsize_x->value() / 2.0;
495 mreq.workspace_parameters.min_corner.y =
ui_->wcenter_y->value() -
ui_->wsize_y->value() / 2.0;
496 mreq.workspace_parameters.min_corner.z =
ui_->wcenter_z->value() -
ui_->wsize_z->value() / 2.0;
497 mreq.workspace_parameters.max_corner.x =
ui_->wcenter_x->value() +
ui_->wsize_x->value() / 2.0;
498 mreq.workspace_parameters.max_corner.y =
ui_->wcenter_y->value() +
ui_->wsize_y->value() / 2.0;
499 mreq.workspace_parameters.max_corner.z =
ui_->wcenter_z->value() +
ui_->wsize_z->value() / 2.0;
504 mreq.goal_constraints.resize(1);
509 void MotionPlanningFrame::configureWorkspace()
529 if (psm && psm->getRobotModelLoader() && psm->getRobotModelLoader()->getModel())
531 const moveit::core::RobotModelPtr& robot_model = psm->getRobotModelLoader()->getModel();
532 const std::vector<moveit::core::JointModel*>& jm = robot_model->getJointModels();
537 joint->setVariableBounds(joint->getName() +
"/" + joint->getLocalVariableNames()[0], bx);
538 joint->setVariableBounds(joint->getName() +
"/" + joint->getLocalVariableNames()[1], by);
542 joint->setVariableBounds(joint->getName() +
"/" + joint->getLocalVariableNames()[0], bx);
543 joint->setVariableBounds(joint->getName() +
"/" + joint->getLocalVariableNames()[1], by);
544 joint->setVariableBounds(joint->getName() +
"/" + joint->getLocalVariableNames()[2], bz);
550 void MotionPlanningFrame::configureForPlanning()
555 move_group_->setNumPlanningAttempts(
ui_->planning_attempts->value());
556 move_group_->setMaxVelocityScalingFactor(
ui_->velocity_scaling_factor->value());
557 move_group_->setMaxAccelerationScalingFactor(
ui_->acceleration_scaling_factor->value());
558 configureWorkspace();
563 void MotionPlanningFrame::remotePlanCallback(
const std_msgs::msg::Empty::ConstSharedPtr& )
568 void MotionPlanningFrame::remoteExecuteCallback(
const std_msgs::msg::Empty::ConstSharedPtr& )
570 executeButtonClicked();
573 void MotionPlanningFrame::remoteStopCallback(
const std_msgs::msg::Empty::ConstSharedPtr& )
578 void MotionPlanningFrame::remoteUpdateStartStateCallback(
const std_msgs::msg::Empty::ConstSharedPtr& )
592 void MotionPlanningFrame::remoteUpdateGoalStateCallback(
const std_msgs::msg::Empty::ConstSharedPtr& )
606 void MotionPlanningFrame::remoteUpdateCustomStartStateCallback(
const moveit_msgs::msg::RobotState::ConstSharedPtr& msg)
608 moveit_msgs::msg::RobotState msg_no_attached(*msg);
609 msg_no_attached.attached_collision_objects.clear();
610 msg_no_attached.is_diff =
true;
617 auto state = std::make_shared<moveit::core::RobotState>(ps->getCurrentState());
624 void MotionPlanningFrame::remoteUpdateCustomGoalStateCallback(
const moveit_msgs::msg::RobotState::ConstSharedPtr& msg)
626 moveit_msgs::msg::RobotState msg_no_attached(*msg);
627 msg_no_attached.attached_collision_objects.clear();
628 msg_no_attached.is_diff =
true;
635 auto state = std::make_shared<moveit::core::RobotState>(ps->getCurrentState());
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
A link from the robot. Contains the constant transform applied to the link and its geometry.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
void changePlanningGroup(const std::string &group)
std::string getCurrentPlanningGroup() const
void setQueryGoalState(const moveit::core::RobotState &goal)
void setQueryStartState(const moveit::core::RobotState &start)
void dropVisualizedTrajectory()
moveit::core::RobotStateConstPtr getQueryStartState() const
void rememberPreviousStartState()
const moveit::core::RobotState & getPreviousState() const
moveit::core::RobotStateConstPtr getQueryGoalState() const
Ui::MotionPlanningUI * ui_
moveit::planning_interface::MoveGroupInterface::PlanPtr current_plan_
std::vector< moveit_msgs::msg::PlannerInterfaceDescription > planner_descriptions_
std::string default_planning_pipeline_
moveit::planning_interface::MoveGroupInterfacePtr move_group_
void constructPlanningRequest(moveit_msgs::msg::MotionPlanRequest &mreq)
MotionPlanningDisplay * planning_display_
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene
void spawnBackgroundJob(const std::function< void()> &job)
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)
bool waitForCurrentRobotState(const rclcpp::Time &t)
wait for robot state more recent than t
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor()
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
Maintain a sequence of waypoints and the time durations between these waypoints.
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_)....
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
std::string append(const std::string &left, const std::string &right)