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"
53 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros_visualization.motion_planning_frame_planning");
55 void MotionPlanningFrame::planButtonClicked()
57 publishSceneIfNeeded();
61 void MotionPlanningFrame::executeButtonClicked()
63 ui_->execute_button->setEnabled(
false);
68 void MotionPlanningFrame::planAndExecuteButtonClicked()
70 publishSceneIfNeeded();
71 ui_->plan_and_execute_button->setEnabled(
false);
72 ui_->execute_button->setEnabled(
false);
77 void MotionPlanningFrame::stopButtonClicked()
79 ui_->stop_button->setEnabled(
false);
83 void MotionPlanningFrame::allowReplanningToggled(
bool checked)
89 void MotionPlanningFrame::allowLookingToggled(
bool checked)
95 void MotionPlanningFrame::pathConstraintsIndexChanged(
int index)
101 std::string
c =
ui_->path_constraints_combo_box->itemText(index).toStdString();
103 RCLCPP_WARN_STREAM(LOGGER,
"Unable to set the path constraints: " <<
c);
110 void MotionPlanningFrame::onClearOctomapClicked()
112 auto req = std::make_shared<std_srvs::srv::Empty::Request>();
113 auto result = clear_octomap_service_client_->async_send_request(req);
115 if (result.wait_for(std::chrono::seconds(0)) != std::future_status::ready)
117 RCLCPP_ERROR(LOGGER,
"Failed to call clear_octomap_service");
119 ui_->clear_octomap_button->setEnabled(
false);
122 bool MotionPlanningFrame::computeCartesianPlan()
124 rclcpp::Time start = rclcpp::Clock().now();
127 std::vector<geometry_msgs::msg::Pose>
waypoints;
128 const std::string& link_name =
move_group_->getEndEffectorLink();
132 RCLCPP_ERROR_STREAM(LOGGER,
"Failed to determine unique end-effector link: " << link_name);
138 double cart_step_size = 0.01;
139 double cart_jump_thresh = 0.0;
140 bool avoid_collisions =
true;
143 moveit_msgs::msg::RobotTrajectory trajectory;
145 move_group_->computeCartesianPath(
waypoints, cart_step_size, cart_jump_thresh, trajectory, avoid_collisions);
149 RCLCPP_INFO(LOGGER,
"Achieved %f %% of Cartesian path",
fraction * 100.);
154 rt.setRobotTrajectoryMsg(*
move_group_->getCurrentState(), trajectory);
156 bool success = time_parameterization.
computeTimeStamps(rt,
ui_->velocity_scaling_factor->value(),
157 ui_->acceleration_scaling_factor->value());
158 RCLCPP_INFO(LOGGER,
"Computing time stamps %s", success ?
"SUCCEEDED" :
"FAILED");
161 current_plan_ = std::make_shared<moveit::planning_interface::MoveGroupInterface::Plan>();
163 current_plan_->planning_time_ = (rclcpp::Clock().now() - start).seconds();
169 bool MotionPlanningFrame::computeJointSpacePlan()
171 current_plan_ = std::make_shared<moveit::planning_interface::MoveGroupInterface::Plan>();
175 void MotionPlanningFrame::computePlanButtonClicked()
181 ui_->result_label->setText(
"Planning...");
183 configureForPlanning();
185 bool success = (
ui_->use_cartesian_path->isEnabled() &&
ui_->use_cartesian_path->checkState()) ?
186 computeCartesianPlan() :
187 computeJointSpacePlan();
191 ui_->execute_button->setEnabled(
true);
192 ui_->result_label->setText(QString(
"Time: ").
append(QString::number(
current_plan_->planning_time_,
'f', 3)));
197 ui_->result_label->setText(
"Failed");
202 void MotionPlanningFrame::computeExecuteButtonClicked()
205 moveit::planning_interface::MoveGroupInterfacePtr mgi(
move_group_);
208 ui_->stop_button->setEnabled(
true);
209 bool success = mgi->execute(*
current_plan_) == moveit::core::MoveItErrorCode::SUCCESS;
210 onFinishedExecution(success);
214 void MotionPlanningFrame::computePlanAndExecuteButtonClicked()
217 moveit::planning_interface::MoveGroupInterfacePtr mgi(
move_group_);
220 configureForPlanning();
224 mgi->setStartStateToCurrentState();
225 ui_->stop_button->setEnabled(
true);
226 if (
ui_->use_cartesian_path->isEnabled() &&
ui_->use_cartesian_path->checkState())
228 if (computeCartesianPlan())
229 computeExecuteButtonClicked();
233 bool success = mgi->move() == moveit::core::MoveItErrorCode::SUCCESS;
234 onFinishedExecution(success);
236 ui_->plan_and_execute_button->setEnabled(
true);
239 void MotionPlanningFrame::computeStopButtonClicked()
245 void MotionPlanningFrame::onFinishedExecution(
bool success)
249 ui_->result_label->setText(
"Executed");
251 ui_->result_label->setText(!
ui_->stop_button->isEnabled() ?
"Stopped" :
"Failed");
253 ui_->stop_button->setEnabled(
false);
256 if (
ui_->start_state_combo_box->currentText() ==
"<current>")
257 startStateTextChanged(
ui_->start_state_combo_box->currentText());
261 if (
ui_->goal_state_combo_box->currentText() ==
"<previous>")
262 goalStateTextChanged(
ui_->goal_state_combo_box->currentText());
265 void MotionPlanningFrame::onNewPlanningSceneState()
268 if (
ui_->start_state_combo_box->currentText() ==
"<current>")
273 if (
ui_->goal_state_combo_box->currentText() ==
"<current>")
277 void MotionPlanningFrame::startStateTextChanged(
const QString& start_state)
281 "update start state");
284 void MotionPlanningFrame::startStateTextChangedExec(
const std::string& start_state)
287 updateQueryStateHelper(start, start_state);
291 void MotionPlanningFrame::goalStateTextChanged(
const QString& goal_state)
295 "update goal state");
298 void MotionPlanningFrame::goalStateTextChangedExec(
const std::string& goal_state)
301 updateQueryStateHelper(goal, goal_state);
305 void MotionPlanningFrame::planningGroupTextChanged(
const QString& planning_group)
314 configureWorkspace();
321 if (v ==
"<random valid>")
323 configureWorkspace();
329 static const int MAX_ATTEMPTS = 100;
330 int attempt_count = 0;
331 while (attempt_count < MAX_ATTEMPTS)
345 if (attempt_count >= MAX_ATTEMPTS)
346 RCLCPP_WARN(LOGGER,
"Unable to find a random collision free configuration after %d attempts", MAX_ATTEMPTS);
355 if (v ==
"<current>")
357 rclcpp::Time t = node_->now();
361 state = ps->getCurrentState();
365 if (v ==
"<same as goal>")
371 if (v ==
"<same as start>")
377 if (v ==
"<previous>")
388 void MotionPlanningFrame::populatePlannersList(
const std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc)
390 ui_->planning_pipeline_combo_box->clear();
393 size_t default_planner_index = 0;
396 QString item_text(
d.pipeline_id.c_str());
400 if (item_text.isEmpty())
401 item_text = QString::fromStdString(
d.name);
402 default_planner_index =
ui_->planning_pipeline_combo_box->count();
404 ui_->planning_pipeline_combo_box->addItem(item_text);
408 ui_->planning_pipeline_combo_box->setItemData(default_planner_index, font, Qt::FontRole);
412 ui_->planning_pipeline_combo_box->setCurrentIndex(default_planner_index);
415 void MotionPlanningFrame::populatePlannerDescription(
const moveit_msgs::msg::PlannerInterfaceDescription& desc)
418 RCLCPP_DEBUG(LOGGER,
"Found %zu planners for group '%s' and pipeline '%s'", desc.planner_ids.size(),
group.c_str(),
419 desc.pipeline_id.c_str());
420 ui_->planning_algorithm_combo_box->clear();
423 ui_->library_label->setText(QString::fromStdString(desc.name));
424 ui_->library_label->setStyleSheet(
"QLabel { color : green; font: bold }");
426 bool found_group =
false;
430 for (
const std::string& planner_id : desc.planner_ids)
432 RCLCPP_DEBUG(LOGGER,
"planner id: %s", planner_id.c_str());
433 if (planner_id ==
group)
435 else if (planner_id.substr(0,
group.length()) ==
group)
437 if (planner_id.size() >
group.length() && planner_id[
group.length()] ==
'[')
439 std::string
id = planner_id.substr(
group.length());
442 id.resize(
id.length() - 1);
443 ui_->planning_algorithm_combo_box->addItem(QString::fromStdString(
id.substr(1)));
449 if (
ui_->planning_algorithm_combo_box->count() == 0 && !found_group)
450 for (
const std::string& planner_id : desc.planner_ids)
451 ui_->planning_algorithm_combo_box->addItem(QString::fromStdString(planner_id));
453 ui_->planning_algorithm_combo_box->insertItem(0,
"<unspecified>");
456 const std::string& default_planner_config =
move_group_->getDefaultPlannerId(found_group ?
group : std::string());
457 int default_index =
ui_->planning_algorithm_combo_box->findText(QString::fromStdString(default_planner_config));
458 if (default_index < 0)
460 ui_->planning_algorithm_combo_box->setCurrentIndex(default_index);
464 ui_->planning_algorithm_combo_box->setItemData(default_index, font, Qt::FontRole);
467 void MotionPlanningFrame::populateConstraintsList()
473 void MotionPlanningFrame::populateConstraintsList(
const std::vector<std::string>& constr)
475 ui_->path_constraints_combo_box->clear();
476 ui_->path_constraints_combo_box->addItem(
"None");
477 for (
const std::string& constraint : constr)
478 ui_->path_constraints_combo_box->addItem(QString::fromStdString(constraint));
484 mreq.num_planning_attempts =
ui_->planning_attempts->value();
485 mreq.allowed_planning_time =
ui_->planning_time->value();
486 mreq.max_velocity_scaling_factor =
ui_->velocity_scaling_factor->value();
487 mreq.max_acceleration_scaling_factor =
ui_->acceleration_scaling_factor->value();
489 mreq.workspace_parameters.min_corner.x =
ui_->wcenter_x->value() -
ui_->wsize_x->value() / 2.0;
490 mreq.workspace_parameters.min_corner.y =
ui_->wcenter_y->value() -
ui_->wsize_y->value() / 2.0;
491 mreq.workspace_parameters.min_corner.z =
ui_->wcenter_z->value() -
ui_->wsize_z->value() / 2.0;
492 mreq.workspace_parameters.max_corner.x =
ui_->wcenter_x->value() +
ui_->wsize_x->value() / 2.0;
493 mreq.workspace_parameters.max_corner.y =
ui_->wcenter_y->value() +
ui_->wsize_y->value() / 2.0;
494 mreq.workspace_parameters.max_corner.z =
ui_->wcenter_z->value() +
ui_->wsize_z->value() / 2.0;
499 mreq.goal_constraints.resize(1);
504 void MotionPlanningFrame::configureWorkspace()
522 if (psm && psm->getRobotModelLoader() && psm->getRobotModelLoader()->getModel())
524 const moveit::core::RobotModelPtr& robot_model = psm->getRobotModelLoader()->getModel();
525 const std::vector<moveit::core::JointModel*>& jm = robot_model->getJointModels();
529 joint->setVariableBounds(joint->getName() +
"/" + joint->getLocalVariableNames()[0], bx);
530 joint->setVariableBounds(joint->getName() +
"/" + joint->getLocalVariableNames()[1], by);
534 joint->setVariableBounds(joint->getName() +
"/" + joint->getLocalVariableNames()[0], bx);
535 joint->setVariableBounds(joint->getName() +
"/" + joint->getLocalVariableNames()[1], by);
536 joint->setVariableBounds(joint->getName() +
"/" + joint->getLocalVariableNames()[2], bz);
541 void MotionPlanningFrame::configureForPlanning()
546 move_group_->setNumPlanningAttempts(
ui_->planning_attempts->value());
547 move_group_->setMaxVelocityScalingFactor(
ui_->velocity_scaling_factor->value());
548 move_group_->setMaxAccelerationScalingFactor(
ui_->acceleration_scaling_factor->value());
549 configureWorkspace();
554 void MotionPlanningFrame::remotePlanCallback(
const std_msgs::msg::Empty::ConstSharedPtr& )
559 void MotionPlanningFrame::remoteExecuteCallback(
const std_msgs::msg::Empty::ConstSharedPtr& )
561 executeButtonClicked();
564 void MotionPlanningFrame::remoteStopCallback(
const std_msgs::msg::Empty::ConstSharedPtr& )
569 void MotionPlanningFrame::remoteUpdateStartStateCallback(
const std_msgs::msg::Empty::ConstSharedPtr& )
583 void MotionPlanningFrame::remoteUpdateGoalStateCallback(
const std_msgs::msg::Empty::ConstSharedPtr& )
597 void MotionPlanningFrame::remoteUpdateCustomStartStateCallback(
const moveit_msgs::msg::RobotState::ConstSharedPtr& msg)
599 moveit_msgs::msg::RobotState msg_no_attached(*msg);
600 msg_no_attached.attached_collision_objects.clear();
601 msg_no_attached.is_diff =
true;
608 auto state = std::make_shared<moveit::core::RobotState>(ps->getCurrentState());
615 void MotionPlanningFrame::remoteUpdateCustomGoalStateCallback(
const moveit_msgs::msg::RobotState::ConstSharedPtr& msg)
617 moveit_msgs::msg::RobotState msg_no_attached(*msg);
618 msg_no_attached.attached_collision_objects.clear();
619 msg_no_attached.is_diff =
true;
626 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
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)
const rclcpp::Logger LOGGER