43#include <rclcpp/rclcpp.hpp>
44#include <rclcpp/version.h>
46#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
57#include <moveit_msgs/action/execute_trajectory.hpp>
58#include <moveit_msgs/srv/query_planner_interfaces.hpp>
59#include <moveit_msgs/srv/get_cartesian_path.hpp>
60#include <moveit_msgs/srv/grasp_planning.hpp>
61#include <moveit_msgs/srv/get_planner_params.hpp>
62#include <moveit_msgs/srv/set_planner_params.hpp>
66#include <std_msgs/msg/string.hpp>
67#include <geometry_msgs/msg/transform_stamped.hpp>
69#if __has_include(<tf2/utils.hpp>)
70#include <tf2/utils.hpp>
74#include <tf2_eigen/tf2_eigen.hpp>
76#if RCLCPP_VERSION_GTE(29, 6, 0)
77#include <tf2_ros/transform_listener.hpp>
80#include <tf2_ros/transform_listener.h>
105#if RCLCPP_VERSION_GTE(17, 0, 0)
108 return rclcpp::SystemDefaultsQoS();
113 return rmw_qos_profile_services_default;
125 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
const rclcpp::Duration& wait_for_servers)
126 : opt_(opt), node_(node), logger_(
moveit::getLogger(
"moveit.ros.move_group_interface")), tf_buffer_(tf_buffer)
130 callback_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive,
132 callback_executor_.add_callback_group(callback_group_, node->get_node_base_interface());
133 callback_thread_ = std::thread([
this]() { callback_executor_.spin(); });
138 std::string error =
"Unable to construct robot model. Please make sure all needed information is on the "
140 RCLCPP_FATAL_STREAM(logger_, error);
141 throw std::runtime_error(error);
146 std::string error =
"Group '" + opt.
group_name +
"' was not found.";
147 RCLCPP_FATAL_STREAM(logger_, error);
148 throw std::runtime_error(error);
154 joint_state_target_ = std::make_shared<moveit::core::RobotState>(
getRobotModel());
155 joint_state_target_->setToDefaultValues();
156 active_target_ = JOINT;
158 look_around_attempts_ = 0;
161 replan_attempts_ = 1;
162 goal_joint_tolerance_ = 1e-4;
163 goal_position_tolerance_ = 1e-4;
164 goal_orientation_tolerance_ = 1e-3;
165 allowed_planning_time_ = 5.0;
166 num_planning_attempts_ = 1;
167 node_->get_parameter_or<
double>(
"robot_description_planning.default_velocity_scaling_factor",
168 max_velocity_scaling_factor_, 0.1);
169 node_->get_parameter_or<
double>(
"robot_description_planning.default_acceleration_scaling_factor",
170 max_acceleration_scaling_factor_, 0.1);
171 initializing_constraints_ =
false;
173 if (joint_model_group_->
isChain())
177 trajectory_event_publisher_ = node_->create_publisher<std_msgs::msg::String>(
181 attached_object_publisher_ = node_->create_publisher<moveit_msgs::msg::AttachedCollisionObject>(
188 move_action_client_ = rclcpp_action::create_client<moveit_msgs::action::MoveGroup>(
190 move_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
191 execute_action_client_ = rclcpp_action::create_client<moveit_msgs::action::ExecuteTrajectory>(
193 execute_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
195 query_service_ = node_->create_client<moveit_msgs::srv::QueryPlannerInterfaces>(
198 get_params_service_ = node_->create_client<moveit_msgs::srv::GetPlannerParams>(
201 set_params_service_ = node_->create_client<moveit_msgs::srv::SetPlannerParams>(
204 cartesian_path_service_ = node_->create_client<moveit_msgs::srv::GetCartesianPath>(
208 RCLCPP_INFO_STREAM(logger_,
"Ready to take commands for planning group " << opt.
group_name <<
'.');
213 if (constraints_init_thread_)
214 constraints_init_thread_->join();
216 callback_executor_.cancel();
218 if (callback_thread_.joinable())
219 callback_thread_.join();
222 const std::shared_ptr<tf2_ros::Buffer>&
getTF()
const
239 return joint_model_group_;
244 return *move_action_client_;
249 auto req = std::make_shared<moveit_msgs::srv::QueryPlannerInterfaces::Request>();
250 auto future_response = query_service_->async_send_request(req);
252 if (future_response.valid())
254 const auto& response = future_response.get();
255 if (!response->planner_interfaces.empty())
257 desc = response->planner_interfaces.front();
266 auto req = std::make_shared<moveit_msgs::srv::QueryPlannerInterfaces::Request>();
267 auto future_response = query_service_->async_send_request(req);
268 if (future_response.valid())
270 const auto& response = future_response.get();
271 if (!response->planner_interfaces.empty())
273 desc = response->planner_interfaces;
280 std::map<std::string, std::string>
getPlannerParams(
const std::string& planner_id,
const std::string& group =
"")
282 auto req = std::make_shared<moveit_msgs::srv::GetPlannerParams::Request>();
283 moveit_msgs::srv::GetPlannerParams::Response::SharedPtr response;
284 req->planner_config = planner_id;
286 std::map<std::string, std::string> result;
288 auto future_response = get_params_service_->async_send_request(req);
289 if (future_response.valid())
291 response = future_response.get();
292 for (
unsigned int i = 0, end = response->params.keys.size(); i < end; ++i)
293 result[response->params.keys[i]] = response->params.values[i];
299 const std::map<std::string, std::string>& params,
bool replace =
false)
301 auto req = std::make_shared<moveit_msgs::srv::SetPlannerParams::Request>();
302 req->planner_config = planner_id;
304 req->replace = replace;
305 for (
const std::pair<const std::string, std::string>& param : params)
307 req->params.keys.push_back(param.first);
308 req->params.values.push_back(param.second);
310 set_params_service_->async_send_request(req);
315 std::string default_planning_pipeline;
316 node_->get_parameter(
"move_group.default_planning_pipeline", default_planning_pipeline);
317 return default_planning_pipeline;
322 if (pipeline_id != planning_pipeline_id_)
324 planning_pipeline_id_ = pipeline_id;
333 return planning_pipeline_id_;
340 if (!planning_pipeline_id_.empty())
341 pipeline_id = planning_pipeline_id_;
343 std::stringstream param_name;
344 param_name <<
"move_group";
345 if (!pipeline_id.empty())
346 param_name <<
"/planning_pipelines/" << pipeline_id;
348 param_name <<
'.' << group;
349 param_name <<
".default_planner_config";
351 std::string default_planner_config;
352 node_->get_parameter(param_name.str(), default_planner_config);
353 return default_planner_config;
358 planner_id_ = planner_id;
368 num_planning_attempts_ = num_planning_attempts;
378 return max_velocity_scaling_factor_;
383 setMaxScalingFactor(max_acceleration_scaling_factor_, value,
"acceleration_scaling_factor", 0.1);
388 return max_acceleration_scaling_factor_;
391 void setMaxScalingFactor(
double& variable,
const double target_value,
const char* factor_name,
double fallback_value)
393 if (target_value > 1.0)
395 RCLCPP_WARN(logger_,
"Limiting max_%s (%.2f) to 1.0.", factor_name, target_value);
398 else if (target_value <= 0.0)
400 node_->get_parameter_or<
double>(std::string(
"robot_description_planning.default_") + factor_name, variable,
402 if (target_value < 0.0)
404 RCLCPP_WARN(logger_,
"max_%s < 0.0! Setting to default: %.2f.", factor_name, variable);
409 variable = target_value;
415 return *joint_state_target_;
420 return *joint_state_target_;
425 considered_start_state_ = start_state;
430 considered_start_state_ = moveit_msgs::msg::RobotState();
437 considered_start_state_ = moveit_msgs::msg::RobotState();
438 considered_start_state_.is_diff =
true;
443 moveit::core::RobotStatePtr s;
450 const std::string& frame,
bool approx)
452 const std::string& eef = end_effector_link.empty() ?
getEndEffectorLink() : end_effector_link;
487 tf2::fromMsg(eef_pose, p);
493 RCLCPP_ERROR(logger_,
"Unable to transform from frame '%s' to frame '%s'", frame.c_str(),
505 end_effector_link_ = end_effector;
510 pose_targets_.erase(end_effector_link);
515 pose_targets_.clear();
520 return end_effector_link_;
525 if (!end_effector_link_.empty())
527 const std::vector<std::string>& possible_eefs =
529 for (
const std::string& possible_eef : possible_eefs)
531 if (
getRobotModel()->getEndEffector(possible_eef)->hasLinkModel(end_effector_link_))
535 static std::string empty;
539 bool setPoseTargets(
const std::vector<geometry_msgs::msg::PoseStamped>& poses,
const std::string& end_effector_link)
541 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
544 RCLCPP_ERROR(logger_,
"No end-effector to set the pose for");
549 pose_targets_[eef] = poses;
551 std::vector<geometry_msgs::msg::PoseStamped>& stored_poses = pose_targets_[eef];
552 for (geometry_msgs::msg::PoseStamped& stored_pose : stored_poses)
553 stored_pose.header.stamp = rclcpp::Time(0);
560 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
561 return pose_targets_.find(eef) != pose_targets_.end();
564 const geometry_msgs::msg::PoseStamped&
getPoseTarget(
const std::string& end_effector_link)
const
566 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
569 std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>>::const_iterator jt = pose_targets_.find(eef);
570 if (jt != pose_targets_.end())
572 if (!jt->second.empty())
573 return jt->second.at(0);
577 static const geometry_msgs::msg::PoseStamped UNKNOWN;
578 RCLCPP_ERROR(logger_,
"Pose for end-effector '%s' not known.", eef.c_str());
582 const std::vector<geometry_msgs::msg::PoseStamped>&
getPoseTargets(
const std::string& end_effector_link)
const
584 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
586 std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>>::const_iterator jt = pose_targets_.find(eef);
587 if (jt != pose_targets_.end())
589 if (!jt->second.empty())
594 static const std::vector<geometry_msgs::msg::PoseStamped> EMPTY;
595 RCLCPP_ERROR(logger_,
"Poses for end-effector '%s' are not known.", eef.c_str());
601 pose_reference_frame_ = pose_reference_frame;
606 return pose_reference_frame_;
611 active_target_ = type;
616 return active_target_;
621 if (!current_state_monitor_)
623 RCLCPP_ERROR(logger_,
"Unable to monitor current robot state");
628 if (!current_state_monitor_->isActive())
629 current_state_monitor_->startStateMonitor();
631 current_state_monitor_->waitForCompleteState(opt_.
group_name, wait);
635 bool getCurrentState(moveit::core::RobotStatePtr& current_state,
double wait_seconds = 1.0)
637 if (!current_state_monitor_)
639 RCLCPP_ERROR(logger_,
"Unable to get current robot state");
644 if (!current_state_monitor_->isActive())
645 current_state_monitor_->startStateMonitor();
647 if (!current_state_monitor_->waitForCurrentState(node_->now(), wait_seconds))
649 RCLCPP_ERROR(logger_,
"Failed to fetch current robot state");
653 current_state = current_state_monitor_->getCurrentState();
659 if (!move_action_client_ || !move_action_client_->action_server_is_ready())
661 RCLCPP_INFO_STREAM(logger_,
"MoveGroup action client/server not ready");
662 return moveit::core::MoveItErrorCode::FAILURE;
664 RCLCPP_INFO_STREAM(logger_,
"MoveGroup action client/server ready");
666 moveit_msgs::action::MoveGroup::Goal goal;
668 goal.planning_options.plan_only =
true;
669 goal.planning_options.look_around =
false;
670 goal.planning_options.replan =
false;
671 goal.planning_options.planning_scene_diff.is_diff =
true;
672 goal.planning_options.planning_scene_diff.robot_state.is_diff =
true;
675 rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
676 std::shared_ptr<moveit_msgs::action::MoveGroup::Result> res;
677 auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::MoveGroup>::SendGoalOptions();
679 send_goal_opts.goal_response_callback =
680 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr& goal_handle) {
684 RCLCPP_INFO(logger_,
"Planning request rejected");
687 RCLCPP_INFO(logger_,
"Planning request accepted");
689 send_goal_opts.result_callback =
690 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::WrappedResult& result) {
697 case rclcpp_action::ResultCode::SUCCEEDED:
698 RCLCPP_INFO(logger_,
"Planning request complete!");
700 case rclcpp_action::ResultCode::ABORTED:
701 RCLCPP_INFO(logger_,
"Planning request aborted");
703 case rclcpp_action::ResultCode::CANCELED:
704 RCLCPP_INFO(logger_,
"Planning request canceled");
707 RCLCPP_INFO(logger_,
"Planning request unknown result code");
712 auto goal_handle_future = move_action_client_->async_send_goal(goal, send_goal_opts);
717 std::this_thread::sleep_for(std::chrono::milliseconds(1));
720 if (code != rclcpp_action::ResultCode::SUCCEEDED)
722 RCLCPP_ERROR_STREAM(logger_,
"MoveGroupInterface::plan() failed or timeout reached");
723 return res->error_code;
726 plan.trajectory = res->planned_trajectory;
727 plan.start_state = res->trajectory_start;
728 plan.planning_time = res->planning_time;
729 RCLCPP_INFO(logger_,
"time taken to generate plan: %g seconds",
plan.planning_time);
731 return res->error_code;
736 if (!move_action_client_ || !move_action_client_->action_server_is_ready())
738 RCLCPP_INFO_STREAM(logger_,
"MoveGroup action client/server not ready");
739 return moveit::core::MoveItErrorCode::FAILURE;
742 moveit_msgs::action::MoveGroup::Goal goal;
744 goal.planning_options.plan_only =
false;
745 goal.planning_options.look_around = can_look_;
746 goal.planning_options.replan = can_replan_;
747 goal.planning_options.replan_delay = replan_delay_;
748 goal.planning_options.planning_scene_diff.is_diff =
true;
749 goal.planning_options.planning_scene_diff.robot_state.is_diff =
true;
752 rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
753 std::shared_ptr<moveit_msgs::action::MoveGroup_Result> res;
754 auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::MoveGroup>::SendGoalOptions();
756 send_goal_opts.goal_response_callback =
757 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr& goal_handle) {
761 RCLCPP_INFO(logger_,
"Plan and Execute request rejected");
764 RCLCPP_INFO(logger_,
"Plan and Execute request accepted");
766 send_goal_opts.result_callback =
767 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::WrappedResult& result) {
774 case rclcpp_action::ResultCode::SUCCEEDED:
775 RCLCPP_INFO(logger_,
"Plan and Execute request complete!");
777 case rclcpp_action::ResultCode::ABORTED:
778 RCLCPP_INFO(logger_,
"Plan and Execute request aborted");
780 case rclcpp_action::ResultCode::CANCELED:
781 RCLCPP_INFO(logger_,
"Plan and Execute request canceled");
784 RCLCPP_INFO(logger_,
"Plan and Execute request unknown result code");
788 auto goal_handle_future = move_action_client_->async_send_goal(goal, send_goal_opts);
790 return moveit::core::MoveItErrorCode::SUCCESS;
795 std::this_thread::sleep_for(std::chrono::milliseconds(1));
798 if (code != rclcpp_action::ResultCode::SUCCEEDED)
800 RCLCPP_ERROR_STREAM(logger_,
"MoveGroupInterface::move() failed or timeout reached");
802 return res->error_code;
806 const std::vector<std::string>& controllers = std::vector<std::string>())
808 if (!execute_action_client_ || !execute_action_client_->action_server_is_ready())
810 RCLCPP_INFO_STREAM(logger_,
"execute_action_client_ client/server not ready");
811 return moveit::core::MoveItErrorCode::FAILURE;
815 rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
816 std::shared_ptr<moveit_msgs::action::ExecuteTrajectory_Result> res;
817 auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::ExecuteTrajectory>::SendGoalOptions();
819 send_goal_opts.goal_response_callback =
820 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::ExecuteTrajectory>::SharedPtr& goal_handle) {
824 RCLCPP_INFO(logger_,
"Execute request rejected");
827 RCLCPP_INFO(logger_,
"Execute request accepted");
829 send_goal_opts.result_callback =
830 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::ExecuteTrajectory>::WrappedResult& result) {
837 case rclcpp_action::ResultCode::SUCCEEDED:
838 RCLCPP_INFO(logger_,
"Execute request success!");
840 case rclcpp_action::ResultCode::ABORTED:
841 RCLCPP_INFO(logger_,
"Execute request aborted");
843 case rclcpp_action::ResultCode::CANCELED:
844 RCLCPP_INFO(logger_,
"Execute request canceled");
847 RCLCPP_INFO(logger_,
"Execute request unknown result code");
852 moveit_msgs::action::ExecuteTrajectory::Goal goal;
853 goal.trajectory = trajectory;
854 goal.controller_names = controllers;
856 auto goal_handle_future = execute_action_client_->async_send_goal(goal, send_goal_opts);
858 return moveit::core::MoveItErrorCode::SUCCESS;
863 std::this_thread::sleep_for(std::chrono::milliseconds(1));
866 if (code != rclcpp_action::ResultCode::SUCCEEDED)
868 RCLCPP_ERROR_STREAM(logger_,
"MoveGroupInterface::execute() failed or timeout reached");
870 return res->error_code;
874 moveit_msgs::msg::RobotTrajectory& msg,
875 const moveit_msgs::msg::Constraints& path_constraints,
bool avoid_collisions,
876 moveit_msgs::msg::MoveItErrorCodes& error_code)
878 auto req = std::make_shared<moveit_msgs::srv::GetCartesianPath::Request>();
879 moveit_msgs::srv::GetCartesianPath::Response::SharedPtr response;
881 req->start_state = considered_start_state_;
884 req->header.stamp =
getClock()->now();
885 req->waypoints = waypoints;
886 req->max_step = step;
887 req->path_constraints = path_constraints;
888 req->avoid_collisions = avoid_collisions;
890 req->max_velocity_scaling_factor = max_velocity_scaling_factor_;
891 req->max_acceleration_scaling_factor = max_acceleration_scaling_factor_;
893 auto future_response = cartesian_path_service_->async_send_request(req);
894 if (future_response.valid())
896 response = future_response.get();
897 error_code = response->error_code;
898 if (response->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
900 msg = response->solution;
901 return response->fraction;
908 error_code.val = error_code.FAILURE;
915 if (trajectory_event_publisher_)
917 std_msgs::msg::String event;
919 trajectory_event_publisher_->publish(event);
923 bool attachObject(
const std::string&
object,
const std::string& link,
const std::vector<std::string>& touch_links)
934 RCLCPP_ERROR(logger_,
"No known link to attach object '%s' to",
object.c_str());
937 moveit_msgs::msg::AttachedCollisionObject aco;
938 aco.object.id = object;
939 aco.link_name.swap(l);
940 if (touch_links.empty())
942 aco.touch_links.push_back(aco.link_name);
946 aco.touch_links = touch_links;
948 aco.object.operation = moveit_msgs::msg::CollisionObject::ADD;
949 attached_object_publisher_->publish(aco);
955 moveit_msgs::msg::AttachedCollisionObject aco;
957 if (!name.empty() && joint_model_group_->
hasLinkModel(name))
959 aco.link_name = name;
963 aco.object.id = name;
965 aco.object.operation = moveit_msgs::msg::CollisionObject::REMOVE;
966 if (aco.link_name.empty() && aco.object.id.empty())
969 const std::vector<std::string>& lnames = joint_model_group_->
getLinkModelNames();
970 for (
const std::string& lname : lnames)
972 aco.link_name = lname;
973 attached_object_publisher_->publish(aco);
978 attached_object_publisher_->publish(aco);
985 return goal_position_tolerance_;
990 return goal_orientation_tolerance_;
995 return goal_joint_tolerance_;
1000 goal_joint_tolerance_ = tolerance;
1005 goal_position_tolerance_ = tolerance;
1010 goal_orientation_tolerance_ = tolerance;
1016 allowed_planning_time_ = seconds;
1021 return allowed_planning_time_;
1026 state = considered_start_state_;
1032 request.num_planning_attempts = num_planning_attempts_;
1033 request.max_velocity_scaling_factor = max_velocity_scaling_factor_;
1034 request.max_acceleration_scaling_factor = max_acceleration_scaling_factor_;
1035 request.allowed_planning_time = allowed_planning_time_;
1036 request.pipeline_id = planning_pipeline_id_;
1037 request.planner_id = planner_id_;
1038 request.workspace_parameters = workspace_parameters_;
1039 request.start_state = considered_start_state_;
1041 if (active_target_ == JOINT)
1043 request.goal_constraints.resize(1);
1047 else if (active_target_ == POSE || active_target_ == POSITION || active_target_ == ORIENTATION)
1050 std::size_t goal_count = 0;
1051 for (
const auto& pose_target : pose_targets_)
1052 goal_count = std::max(goal_count, pose_target.second.size());
1058 request.goal_constraints.resize(goal_count);
1060 for (
const auto& pose_target : pose_targets_)
1062 for (std::size_t i = 0; i < pose_target.second.size(); ++i)
1065 pose_target.first, pose_target.second[i], goal_position_tolerance_, goal_orientation_tolerance_);
1066 if (active_target_ == ORIENTATION)
1067 c.position_constraints.clear();
1068 if (active_target_ == POSITION)
1069 c.orientation_constraints.clear();
1075 RCLCPP_ERROR(logger_,
"Unable to construct MotionPlanRequest representation");
1077 if (path_constraints_)
1078 request.path_constraints = *path_constraints_;
1079 if (trajectory_constraints_)
1080 request.trajectory_constraints = *trajectory_constraints_;
1090 path_constraints_ = std::make_unique<moveit_msgs::msg::Constraints>(constraint);
1095 if (constraints_storage_)
1098 if (constraints_storage_->getConstraints(msg_m, constraint, robot_model_->getName(), opt_.
group_name))
1101 std::make_unique<moveit_msgs::msg::Constraints>(
static_cast<moveit_msgs::msg::Constraints
>(*msg_m));
1113 path_constraints_.reset();
1118 trajectory_constraints_ = std::make_unique<moveit_msgs::msg::TrajectoryConstraints>(constraint);
1123 trajectory_constraints_.reset();
1128 while (initializing_constraints_)
1130 std::chrono::duration<double> d(0.01);
1131 rclcpp::sleep_for(std::chrono::duration_cast<std::chrono::nanoseconds>(d), rclcpp::Context::SharedPtr(
nullptr));
1134 std::vector<std::string> c;
1135 if (constraints_storage_)
1136 constraints_storage_->getKnownConstraints(c, robot_model_->getName(), opt_.
group_name);
1143 if (path_constraints_)
1145 return *path_constraints_;
1149 return moveit_msgs::msg::Constraints();
1155 if (trajectory_constraints_)
1157 return *trajectory_constraints_;
1161 return moveit_msgs::msg::TrajectoryConstraints();
1167 initializing_constraints_ =
true;
1168 if (constraints_init_thread_)
1169 constraints_init_thread_->join();
1170 constraints_init_thread_ =
1171 std::make_unique<std::thread>([
this, host, port] { initializeConstraintsStorageThread(host, port); });
1174 void setWorkspace(
double minx,
double miny,
double minz,
double maxx,
double maxy,
double maxz)
1176 workspace_parameters_.header.frame_id =
getRobotModel()->getModelFrame();
1177 workspace_parameters_.header.stamp =
getClock()->now();
1178 workspace_parameters_.min_corner.x = minx;
1179 workspace_parameters_.min_corner.y = miny;
1180 workspace_parameters_.min_corner.z = minz;
1181 workspace_parameters_.max_corner.x = maxx;
1182 workspace_parameters_.max_corner.y = maxy;
1183 workspace_parameters_.max_corner.z = maxz;
1188 return node_->get_clock();
1192 void initializeConstraintsStorageThread(
const std::string& host,
unsigned int port)
1198 conn->setParams(host, port);
1199 if (conn->connect())
1201 constraints_storage_ = std::make_unique<moveit_warehouse::ConstraintsStorage>(conn);
1204 catch (std::exception& ex)
1206 RCLCPP_ERROR(logger_,
"%s", ex.what());
1208 initializing_constraints_ =
false;
1212 rclcpp::Node::SharedPtr node_;
1213 rclcpp::Logger logger_;
1214 rclcpp::CallbackGroup::SharedPtr callback_group_;
1215 rclcpp::executors::SingleThreadedExecutor callback_executor_;
1216 std::thread callback_thread_;
1217 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
1218 moveit::core::RobotModelConstPtr robot_model_;
1219 planning_scene_monitor::CurrentStateMonitorPtr current_state_monitor_;
1221 std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::MoveGroup>> move_action_client_;
1224 std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::ExecuteTrajectory>> execute_action_client_;
1227 moveit_msgs::msg::RobotState considered_start_state_;
1228 moveit_msgs::msg::WorkspaceParameters workspace_parameters_;
1229 double allowed_planning_time_;
1230 std::string planning_pipeline_id_;
1231 std::string planner_id_;
1232 unsigned int num_planning_attempts_;
1233 double max_velocity_scaling_factor_;
1234 double max_acceleration_scaling_factor_;
1235 double goal_joint_tolerance_;
1236 double goal_position_tolerance_;
1237 double goal_orientation_tolerance_;
1239 int32_t look_around_attempts_;
1241 int32_t replan_attempts_;
1242 double replan_delay_;
1245 moveit::core::RobotStatePtr joint_state_target_;
1250 std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>> pose_targets_;
1253 ActiveTargetType active_target_;
1254 std::unique_ptr<moveit_msgs::msg::Constraints> path_constraints_;
1255 std::unique_ptr<moveit_msgs::msg::TrajectoryConstraints> trajectory_constraints_;
1256 std::string end_effector_link_;
1257 std::string pose_reference_frame_;
1260 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr trajectory_event_publisher_;
1261 rclcpp::Publisher<moveit_msgs::msg::AttachedCollisionObject>::SharedPtr attached_object_publisher_;
1262 rclcpp::Client<moveit_msgs::srv::QueryPlannerInterfaces>::SharedPtr query_service_;
1263 rclcpp::Client<moveit_msgs::srv::GetPlannerParams>::SharedPtr get_params_service_;
1264 rclcpp::Client<moveit_msgs::srv::SetPlannerParams>::SharedPtr set_params_service_;
1265 rclcpp::Client<moveit_msgs::srv::GetCartesianPath>::SharedPtr cartesian_path_service_;
1267 std::unique_ptr<moveit_warehouse::ConstraintsStorage> constraints_storage_;
1268 std::unique_ptr<std::thread> constraints_init_thread_;
1269 bool initializing_constraints_;
1273 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
1274 const rclcpp::Duration& wait_for_servers)
1275 : logger_(
moveit::getLogger(
"moveit.ros.move_group_interface"))
1278 throw std::runtime_error(
"ROS does not seem to be running");
1284 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
1285 const rclcpp::Duration& wait_for_servers)
1286 : logger_(
moveit::getLogger(
"moveit.ros.move_group_interface"))
1297 : remembered_joint_values_(std::move(other.remembered_joint_values_))
1298 , impl_(other.impl_)
1299 , logger_(std::move(other.logger_))
1301 other.impl_ =
nullptr;
1309 impl_ = other.impl_;
1310 logger_ = other.logger_;
1311 remembered_joint_values_ = std::move(other.remembered_joint_values_);
1312 other.impl_ =
nullptr;
1332 return impl_->
getTF();
1351 const std::string& group)
const
1357 const std::map<std::string, std::string>& params,
bool replace)
1419 return impl_->
move(
false);
1429 return impl_->
move(
true);
1433 const std::vector<std::string>& controllers)
1435 return impl_->
execute(
plan.trajectory,
false, controllers);
1439 const std::vector<std::string>& controllers)
1441 return impl_->
execute(trajectory,
false, controllers);
1446 return impl_->
execute(
plan.trajectory,
true, controllers);
1450 const std::vector<std::string>& controllers)
1452 return impl_->
execute(trajectory,
true, controllers);
1461 moveit_msgs::msg::RobotTrajectory& trajectory,
bool avoid_collisions,
1462 moveit_msgs::msg::MoveItErrorCodes* error_code)
1464 moveit_msgs::msg::Constraints path_constraints_tmp;
1465 return computeCartesianPath(waypoints, eef_step, trajectory, moveit_msgs::msg::Constraints(), avoid_collisions,
1470 moveit_msgs::msg::RobotTrajectory& trajectory,
1471 const moveit_msgs::msg::Constraints& path_constraints,
1472 bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes* error_code)
1476 return impl_->
computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, *error_code);
1480 moveit_msgs::msg::MoveItErrorCodes err_tmp;
1481 err_tmp.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
1482 moveit_msgs::msg::MoveItErrorCodes& err = error_code ? *error_code : err_tmp;
1483 return impl_->
computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, err);
1525 std::map<std::string, std::vector<double>>::const_iterator it = remembered_joint_values_.find(name);
1526 std::map<std::string, double> positions;
1528 if (it != remembered_joint_values_.cend())
1531 for (
size_t x = 0; x < names.size(); ++x)
1533 positions[names[x]] = it->second[x];
1540 RCLCPP_ERROR(logger_,
"The requested named target '%s' does not exist, returning empty positions.", name.c_str());
1548 std::map<std::string, std::vector<double>>::const_iterator it = remembered_joint_values_.find(name);
1549 if (it != remembered_joint_values_.end())
1560 RCLCPP_ERROR(logger_,
"The requested named target '%s' does not exist", name.c_str());
1573 if (joint_values.size() != n_group_joints)
1575 RCLCPP_DEBUG_STREAM(logger_,
"Provided joint value list has length " << joint_values.size() <<
" but group "
1577 <<
" has " << n_group_joints <<
" joints");
1588 for (
const auto& pair : variable_values)
1590 if (std::find(allowed.begin(), allowed.end(), pair.first) == allowed.end())
1592 RCLCPP_ERROR_STREAM(logger_,
"joint variable " << pair.first <<
" is not part of group "
1604 const std::vector<double>& variable_values)
1606 if (variable_names.size() != variable_values.size())
1608 RCLCPP_ERROR_STREAM(logger_,
"sizes of name and position arrays do not match");
1612 for (
const auto& variable_name : variable_names)
1614 if (std::find(allowed.begin(), allowed.end(), variable_name) == allowed.end())
1616 RCLCPP_ERROR_STREAM(logger_,
"joint variable " << variable_name <<
" is not part of group "
1636 std::vector<double> values(1, value);
1650 RCLCPP_ERROR_STREAM(logger_,
1661 const std::string& end_effector_link)
1667 const std::string& end_effector_link)
1669 return impl_->
setJointValueTarget(eef_pose.pose, end_effector_link, eef_pose.header.frame_id,
false);
1674 geometry_msgs::msg::Pose msg = tf2::toMsg(eef_pose);
1679 const std::string& end_effector_link)
1685 const std::string& end_effector_link)
1687 return impl_->
setJointValueTarget(eef_pose.pose, end_effector_link, eef_pose.header.frame_id,
true);
1691 const std::string& end_effector_link)
1693 geometry_msgs::msg::Pose msg = tf2::toMsg(eef_pose);
1741 std::vector<geometry_msgs::msg::PoseStamped> pose_msg(1);
1742 pose_msg[0].pose = tf2::toMsg(pose);
1744 pose_msg[0].header.stamp = impl_->
getClock()->now();
1750 std::vector<geometry_msgs::msg::PoseStamped> pose_msg(1);
1751 pose_msg[0].pose = target;
1753 pose_msg[0].header.stamp = impl_->
getClock()->now();
1758 const std::string& end_effector_link)
1760 std::vector<geometry_msgs::msg::PoseStamped> targets(1, target);
1766 std::vector<geometry_msgs::msg::PoseStamped> pose_out(target.size());
1767 rclcpp::Time tm = impl_->
getClock()->now();
1769 for (std::size_t i = 0; i < target.size(); ++i)
1771 pose_out[i].pose = tf2::toMsg(target[i]);
1772 pose_out[i].header.stamp = tm;
1773 pose_out[i].header.frame_id = frame_id;
1779 const std::string& end_effector_link)
1781 std::vector<geometry_msgs::msg::PoseStamped> target_stamped(target.size());
1782 rclcpp::Time tm = impl_->
getClock()->now();
1784 for (std::size_t i = 0; i < target.size(); ++i)
1786 target_stamped[i].pose = target[i];
1787 target_stamped[i].header.stamp = tm;
1788 target_stamped[i].header.frame_id = frame_id;
1794 const std::string& end_effector_link)
1798 RCLCPP_ERROR(logger_,
"No pose specified as goal target");
1813const std::vector<geometry_msgs::msg::PoseStamped>&
1821inline void transformPose(
const tf2_ros::Buffer& tf_buffer,
const std::string& desired_frame,
1822 geometry_msgs::msg::PoseStamped& target)
1824 if (desired_frame != target.header.frame_id)
1826 geometry_msgs::msg::PoseStamped target_in(target);
1827 tf_buffer.transform(target_in, target, desired_frame);
1829 target.header.stamp = rclcpp::Time(0);
1836 geometry_msgs::msg::PoseStamped target;
1844 target.pose.orientation.x = 0.0;
1845 target.pose.orientation.y = 0.0;
1846 target.pose.orientation.z = 0.0;
1847 target.pose.orientation.w = 1.0;
1851 target.pose.position.x = x;
1852 target.pose.position.y = y;
1853 target.pose.position.z = z;
1861 geometry_msgs::msg::PoseStamped target;
1869 target.pose.position.x = 0.0;
1870 target.pose.position.y = 0.0;
1871 target.pose.position.z = 0.0;
1876 target.pose.orientation = tf2::toMsg(q);
1883 const std::string& end_effector_link)
1885 geometry_msgs::msg::PoseStamped target;
1893 target.pose.position.x = 0.0;
1894 target.pose.position.y = 0.0;
1895 target.pose.position.z = 0.0;
1899 target.pose.orientation.x = x;
1900 target.pose.orientation.y = y;
1901 target.pose.orientation.z = z;
1902 target.pose.orientation.w = w;
1967 moveit::core::RobotStatePtr current_state;
1968 std::vector<double> values;
1970 current_state->copyJointGroupPositions(
getName(), values);
1976 std::vector<double> r;
1983 const std::string& eef = end_effector_link.empty() ?
getEndEffectorLink() : end_effector_link;
1984 Eigen::Isometry3d pose;
1988 RCLCPP_ERROR(logger_,
"No end-effector specified");
1992 moveit::core::RobotStatePtr current_state;
1998 pose = current_state->getGlobalLinkTransform(lm);
2001 geometry_msgs::msg::PoseStamped pose_msg;
2002 pose_msg.header.stamp = impl_->
getClock()->now();
2003 pose_msg.header.frame_id = impl_->
getRobotModel()->getModelFrame();
2004 pose_msg.pose = tf2::toMsg(pose);
2010 const std::string& eef = end_effector_link.empty() ?
getEndEffectorLink() : end_effector_link;
2011 Eigen::Isometry3d pose;
2015 RCLCPP_ERROR(logger_,
"No end-effector specified");
2019 moveit::core::RobotStatePtr current_state;
2024 pose = current_state->getGlobalLinkTransform(lm);
2027 geometry_msgs::msg::PoseStamped pose_msg;
2028 pose_msg.header.stamp = impl_->
getClock()->now();
2029 pose_msg.header.frame_id = impl_->
getRobotModel()->getModelFrame();
2030 pose_msg.pose = tf2::toMsg(pose);
2036 std::vector<double> result;
2037 const std::string& eef = end_effector_link.empty() ?
getEndEffectorLink() : end_effector_link;
2040 RCLCPP_ERROR(logger_,
"No end-effector specified");
2044 moveit::core::RobotStatePtr current_state;
2051 geometry_msgs::msg::TransformStamped tfs = tf2::eigenToTransform(current_state->getGlobalLinkTransform(lm));
2052 double pitch, roll, yaw;
2053 tf2::getEulerYPR<geometry_msgs::msg::Quaternion>(tfs.transform.rotation, yaw, pitch, roll);
2080 moveit::core::RobotStatePtr current_state;
2082 return current_state;
2087 remembered_joint_values_[name] = values;
2092 remembered_joint_values_.erase(name);
2097 impl_->can_look_ = flag;
2098 RCLCPP_DEBUG(logger_,
"Looking around: %s", flag ?
"yes" :
"no");
2105 RCLCPP_ERROR(logger_,
"Tried to set negative number of look-around attempts");
2109 RCLCPP_DEBUG_STREAM(logger_,
"Look around attempts: " << attempts);
2110 impl_->look_around_attempts_ = attempts;
2116 impl_->can_replan_ = flag;
2117 RCLCPP_DEBUG(logger_,
"Replanning: %s", flag ?
"yes" :
"no");
2124 RCLCPP_ERROR(logger_,
"Tried to set negative number of replan attempts");
2128 RCLCPP_DEBUG_STREAM(logger_,
"Replan Attempts: " << attempts);
2129 impl_->replan_attempts_ = attempts;
2137 RCLCPP_ERROR(logger_,
"Tried to set negative replan delay");
2141 RCLCPP_DEBUG_STREAM(logger_,
"Replan Delay: " << delay);
2142 impl_->replan_delay_ = delay;
2193 impl_->
setWorkspace(minx, miny, minz, maxx, maxy, maxz);
2210 return impl_->node_;
2225 return attachObject(
object, link, std::vector<std::string>());
2229 const std::vector<std::string>& touch_links)
bool isChain() const
Check if this group is a linear chain.
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
const std::vector< std::string > & getJointModelNames() const
Get the names of the joints in this group. These are the names of the joints returned by getJointMode...
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute random values for the state of the joint group.
const std::pair< std::string, std::string > & getEndEffectorParentGroup() const
Get the name of the group this end-effector attaches to (first) and the name of the link in that grou...
const std::string & getName() const
Get the name of the joint group.
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Throw an exception if the joint is not part of this group.
bool hasLinkModel(const std::string &link) const
Check if a link is part of this group.
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
bool getVariableDefaultPositions(const std::string &name, std::map< std::string, double > &values) const
Get the values that correspond to a named state as read from the URDF. Return false on failure.
const std::vector< std::string > & getDefaultStateNames() const
Get the names of the known default states (as specified in the SRDF)
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
A link from the robot. Contains the constant transform applied to the link and its geometry.
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
bool satisfiesBounds(double margin=0.0) const
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
random_numbers::RandomNumberGenerator & getRandomNumberGenerator()
Return the instance of a random number generator.
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
void setJointPositions(const std::string &joint_name, const double *position)
rclcpp_action::Client< moveit_msgs::action::MoveGroup > & getMoveGroupClient() const
bool startStateMonitor(double wait)
void setPlanningPipelineId(const std::string &pipeline_id)
void setPoseReferenceFrame(const std::string &pose_reference_frame)
double getGoalPositionTolerance() const
std::string getDefaultPlanningPipelineId() const
~MoveGroupInterfaceImpl()
rclcpp::Clock::SharedPtr getClock()
void setEndEffectorLink(const std::string &end_effector)
void constructGoal(moveit_msgs::action::MoveGroup::Goal &goal) const
double getPlanningTime() const
void constructRobotState(moveit_msgs::msg::RobotState &state) const
std::string getDefaultPlannerId(const std::string &group) const
bool setPathConstraints(const std::string &constraint)
void setStartState(const moveit::core::RobotState &start_state)
const std::string & getEndEffector() const
double getGoalJointTolerance() const
void setMaxScalingFactor(double &variable, const double target_value, const char *factor_name, double fallback_value)
void setMaxAccelerationScalingFactor(double value)
void clearPathConstraints()
void setGoalOrientationTolerance(double tolerance)
bool getCurrentState(moveit::core::RobotStatePtr ¤t_state, double wait_seconds=1.0)
const std::string & getPoseReferenceFrame() const
void clearPoseTarget(const std::string &end_effector_link)
bool attachObject(const std::string &object, const std::string &link, const std::vector< std::string > &touch_links)
void setGoalPositionTolerance(double tolerance)
const std::string & getEndEffectorLink() const
std::map< std::string, std::string > getPlannerParams(const std::string &planner_id, const std::string &group="")
void initializeConstraintsStorage(const std::string &host, unsigned int port)
void setPlannerId(const std::string &planner_id)
double getGoalOrientationTolerance() const
moveit_msgs::msg::Constraints getPathConstraints() const
void setTargetType(ActiveTargetType type)
void setPathConstraints(const moveit_msgs::msg::Constraints &constraint)
ActiveTargetType getTargetType() const
double computeCartesianPath(const std::vector< geometry_msgs::msg::Pose > &waypoints, double step, moveit_msgs::msg::RobotTrajectory &msg, const moveit_msgs::msg::Constraints &path_constraints, bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes &error_code)
void setMaxVelocityScalingFactor(double value)
const moveit::core::RobotState & getTargetRobotState() const
void setNumPlanningAttempts(unsigned int num_planning_attempts)
const std::string & getPlannerId() const
double getMaxVelocityScalingFactor() const
std::vector< std::string > getKnownConstraints() const
void setGoalJointTolerance(double tolerance)
void setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints &constraint)
const std::shared_ptr< tf2_ros::Buffer > & getTF() const
moveit::core::MoveItErrorCode move(bool wait)
void constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest &request) const
void setPlanningTime(double seconds)
moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints() const
const moveit::core::JointModelGroup * getJointModelGroup() const
double getMaxAccelerationScalingFactor() const
MoveGroupInterfaceImpl(const rclcpp::Node::SharedPtr &node, const Options &opt, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer, const rclcpp::Duration &wait_for_servers)
bool setPoseTargets(const std::vector< geometry_msgs::msg::PoseStamped > &poses, const std::string &end_effector_link)
const geometry_msgs::msg::PoseStamped & getPoseTarget(const std::string &end_effector_link) const
void clearTrajectoryConstraints()
moveit::core::MoveItErrorCode execute(const moveit_msgs::msg::RobotTrajectory &trajectory, bool wait, const std::vector< std::string > &controllers=std::vector< std::string >())
bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription &desc)
const Options & getOptions() const
void setStartState(const moveit_msgs::msg::RobotState &start_state)
const moveit::core::RobotModelConstPtr & getRobotModel() const
const std::vector< geometry_msgs::msg::PoseStamped > & getPoseTargets(const std::string &end_effector_link) const
bool detachObject(const std::string &name)
bool setJointValueTarget(const geometry_msgs::msg::Pose &eef_pose, const std::string &end_effector_link, const std::string &frame, bool approx)
moveit::core::RobotStatePtr getStartState()
bool hasPoseTarget(const std::string &end_effector_link) const
void setPlannerParams(const std::string &planner_id, const std::string &group, const std::map< std::string, std::string > ¶ms, bool replace=false)
bool getInterfaceDescriptions(std::vector< moveit_msgs::msg::PlannerInterfaceDescription > &desc)
void setStartStateToCurrentState()
moveit::core::RobotState & getTargetRobotState()
moveit::core::MoveItErrorCode plan(Plan &plan)
const std::string & getPlanningPipelineId() const
void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
Client class to conveniently use the ROS interfaces provided by the move_group node.
std::vector< double > getRandomJointValues() const
Get random joint values for the joints planned for by this instance (see getJoints())
double computeCartesianPath(const std::vector< geometry_msgs::msg::Pose > &waypoints, double eef_step, double, moveit_msgs::msg::RobotTrajectory &trajectory, bool avoid_collisions=true, moveit_msgs::msg::MoveItErrorCodes *error_code=nullptr)
Compute a Cartesian path that follows specified waypoints with a step size of at most eef_step meters...
void setMaxVelocityScalingFactor(double max_velocity_scaling_factor)
Set a scaling factor for optionally reducing the maximum joint velocity. Allowed values are in (0,...
const std::string & getEndEffectorLink() const
Get the current end-effector link. This returns the value set by setEndEffectorLink() (or indirectly ...
static const std::string ROBOT_DESCRIPTION
Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description'.
const std::vector< std::string > & getNamedTargets() const
Get the names of the named robot states available as targets, both either remembered states or defaul...
std::map< std::string, std::string > getPlannerParams(const std::string &planner_id, const std::string &group="") const
Get the planner parameters for given group and planner_id.
void stop()
Stop any trajectory execution, if one is active.
MoveGroupInterface(const rclcpp::Node::SharedPtr &node, const Options &opt, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer=std::shared_ptr< tf2_ros::Buffer >(), const rclcpp::Duration &wait_for_servers=rclcpp::Duration::from_seconds(-1))
Construct a MoveGroupInterface instance call using a specified set of options opt.
const std::string & getPlannerId() const
Get the current planner_id.
void setReplanDelay(double delay)
Sleep this duration between replanning attempts (in walltime seconds)
MoveGroupInterface & operator=(const MoveGroupInterface &)=delete
moveit::core::MoveItErrorCode plan(Plan &plan)
Compute a motion plan that takes the group declared in the constructor from the current state to the ...
void setGoalTolerance(double tolerance)
Set the tolerance that is used for reaching the goal. For joint state goals, this will be distance fo...
void setGoalPositionTolerance(double tolerance)
Set the position tolerance that is used for reaching the goal when moving to a pose.
const std::string & getPlanningFrame() const
Get the name of the frame in which the robot is planning.
bool setPoseTargets(const EigenSTL::vector_Isometry3d &end_effector_pose, const std::string &end_effector_link="")
Set goal poses for end_effector_link.
bool setPoseTarget(const Eigen::Isometry3d &end_effector_pose, const std::string &end_effector_link="")
Set the goal pose of the end-effector end_effector_link.
moveit::core::MoveItErrorCode asyncMove()
Plan and execute a trajectory that takes the group of joints declared in the constructor to the speci...
void setPlanningPipelineId(const std::string &pipeline_id)
Specify a planning pipeline to be used for further planning.
double getGoalJointTolerance() const
Get the tolerance that is used for reaching a joint goal. This is distance for each joint in configur...
bool setEndEffectorLink(const std::string &end_effector_link)
Specify the parent link of the end-effector. This end_effector_link will be used in calls to pose tar...
void setStartStateToCurrentState()
Set the starting state for planning to be that reported by the robot's joint state publication.
bool getInterfaceDescriptions(std::vector< moveit_msgs::msg::PlannerInterfaceDescription > &desc) const
Get the descriptions of all planning plugins loaded by the action server.
void setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor)
Set a scaling factor for optionally reducing the maximum joint acceleration. Allowed values are in (0...
bool setPositionTarget(double x, double y, double z, const std::string &end_effector_link="")
Set the goal position of the end-effector end_effector_link to be (x, y, z).
const std::string & getEndEffector() const
Get the current end-effector name. This returns the value set by setEndEffector() (or indirectly by s...
void clearPathConstraints()
Specify that no path constraints are to be used. This removes any path constraints set in previous ca...
bool attachObject(const std::string &object, const std::string &link="")
Given the name of an object in the planning scene, make the object attached to a link of the robot....
std::string getDefaultPlanningPipelineId() const
moveit_msgs::msg::Constraints getPathConstraints() const
Get the actual set of constraints in use with this MoveGroupInterface.
void setNumPlanningAttempts(unsigned int num_planning_attempts)
Set the number of times the motion plan is to be computed from scratch before the shortest solution i...
rclcpp_action::Client< moveit_msgs::action::MoveGroup > & getMoveGroupClient() const
Get the move_group action client used by the MoveGroupInterface. The client can be used for querying ...
std::vector< double > getCurrentJointValues() const
Get the current joint values for the joints planned for by this instance (see getJoints())
bool setNamedTarget(const std::string &name)
Set the current joint values to be ones previously remembered by rememberJointValues() or,...
const std::vector< std::string > & getJointNames() const
Get vector of names of joints available in move group.
moveit::core::MoveItErrorCode move()
Plan and execute a trajectory that takes the group of joints declared in the constructor to the speci...
void setReplanAttempts(int32_t attempts)
Maximum number of replanning attempts.
void allowReplanning(bool flag)
Specify whether the robot is allowed to replan if it detects changes in the environment.
moveit::core::RobotModelConstPtr getRobotModel() const
Get the RobotModel object.
moveit::core::MoveItErrorCode execute(const Plan &plan, const std::vector< std::string > &controllers=std::vector< std::string >())
Given a plan, execute it while waiting for completion.
void constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest &request)
Build the MotionPlanRequest that would be sent to the move_group action with plan() or move() and sto...
bool setOrientationTarget(double x, double y, double z, double w, const std::string &end_effector_link="")
Set the goal orientation of the end-effector end_effector_link to be the quaternion (x,...
bool setJointValueTarget(const std::vector< double > &group_variable_values)
Set the JointValueTarget and use it for future planning requests.
void clearTrajectoryConstraints()
const rclcpp::Node::SharedPtr & getNode() const
Get the ROS node handle of this instance operates on.
bool setRPYTarget(double roll, double pitch, double yaw, const std::string &end_effector_link="")
Set the goal orientation of the end-effector end_effector_link to be (roll,pitch,yaw) radians.
void setGoalOrientationTolerance(double tolerance)
Set the orientation tolerance that is used for reaching the goal when moving to a pose.
void clearPoseTarget(const std::string &end_effector_link="")
Forget pose(s) specified for end_effector_link.
const geometry_msgs::msg::PoseStamped & getPoseTarget(const std::string &end_effector_link="") const
void setGoalJointTolerance(double tolerance)
Set the joint tolerance (for each joint) that is used for reaching the goal when moving to a joint va...
std::string getDefaultPlannerId(const std::string &group="") const
Get the default planner of the current planning pipeline for the given group (or the pipeline's defau...
void setRandomTarget()
Set the joint state goal to a random joint configuration.
moveit::core::RobotStatePtr getCurrentState(double wait=1) const
Get the current state of the robot within the duration specified by wait.
void getJointValueTarget(std::vector< double > &group_variable_values) const
Get the current joint state goal in a form compatible to setJointValueTarget()
const std::vector< std::string > & getActiveJoints() const
Get only the active (actuated) joints this instance operates on.
void rememberJointValues(const std::string &name)
Remember the current joint values (of the robot being monitored) under name. These can be used by set...
void setLookAroundAttempts(int32_t attempts)
How often is the system allowed to move the camera to update environment model when looking.
bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription &desc) const
Get the description of the default planning plugin loaded by the action server.
const std::string & getName() const
Get the name of the group this instance operates on.
moveit::core::MoveItErrorCode asyncExecute(const Plan &plan, const std::vector< std::string > &controllers=std::vector< std::string >())
Given a plan, execute it without waiting for completion.
const std::vector< std::string > & getJoints() const
Get all the joints this instance operates on (including fixed joints)
bool detachObject(const std::string &name="")
Detach an object. name specifies the name of the object attached to this group, or the name of the li...
void setPoseReferenceFrame(const std::string &pose_reference_frame)
Specify which reference frame to assume for poses specified without a reference frame.
const std::shared_ptr< tf2_ros::Buffer > & getTF() const
Get the tf2_ros::Buffer.
const std::vector< geometry_msgs::msg::PoseStamped > & getPoseTargets(const std::string &end_effector_link="") const
double getMaxVelocityScalingFactor() const
Get the max velocity scaling factor set by setMaxVelocityScalingFactor().
moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints() const
const std::vector< std::string > & getLinkNames() const
Get vector of names of links available in move group.
double getMaxAccelerationScalingFactor() const
Get the max acceleration scaling factor set by setMaxAccelerationScalingFactor().
void setStartState(const moveit_msgs::msg::RobotState &start_state)
If a different start state should be considered instead of the current state of the robot,...
bool setPathConstraints(const std::string &constraint)
Specify a set of path constraints to use. The constraints are looked up by name from the Mongo databa...
void clearPoseTargets()
Forget any poses specified for all end-effectors.
void setPlannerId(const std::string &planner_id)
Specify a planner to be used for further planning.
bool setEndEffector(const std::string &eef_name)
Specify the name of the end-effector to use. This is equivalent to setting the EndEffectorLink to the...
const std::string & getPoseReferenceFrame() const
Get the reference frame set by setPoseReferenceFrame(). By default this is the reference frame of the...
const std::string & getPlanningPipelineId() const
Get the current planning_pipeline_id.
void setConstraintsDatabase(const std::string &host, unsigned int port)
Specify where the database server that holds known constraints resides.
std::vector< double > getCurrentRPY(const std::string &end_effector_link="") const
Get the roll-pitch-yaw (XYZ) for the end-effector end_effector_link. If end_effector_link is empty (t...
void forgetJointValues(const std::string &name)
Forget the joint values remembered under name.
std::vector< std::string > getKnownConstraints() const
Get the names of the known constraints as read from the Mongo database, if a connection was achieved.
void setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints &constraint)
const moveit::core::RobotState & getTargetRobotState() const
geometry_msgs::msg::PoseStamped getRandomPose(const std::string &end_effector_link="") const
Get a random reachable pose for the end-effector end_effector_link. If end_effector_link is empty (th...
double getGoalOrientationTolerance() const
Get the tolerance that is used for reaching an orientation goal. This is the tolerance for roll,...
void allowLooking(bool flag)
Specify whether the robot is allowed to look around before moving if it determines it should (default...
std::map< std::string, double > getNamedTargetValues(const std::string &name) const
Get the joint angles for targets specified by name.
geometry_msgs::msg::PoseStamped getCurrentPose(const std::string &end_effector_link="") const
Get the pose for the end-effector end_effector_link. If end_effector_link is empty (the default value...
bool startStateMonitor(double wait=1.0)
When reasoning about the current state of a robot, a CurrentStateMonitor instance is automatically co...
unsigned int getVariableCount() const
Get the number of variables used to describe the state of this group. This is larger or equal to the ...
double getGoalPositionTolerance() const
Get the tolerance that is used for reaching a position goal. This is be the radius of a sphere where ...
double getPlanningTime() const
Get the number of seconds set by setPlanningTime()
void setPlanningTime(double seconds)
Specify the maximum amount of time to use when planning.
bool setApproximateJointValueTarget(const geometry_msgs::msg::Pose &eef_pose, const std::string &end_effector_link="")
Set the joint state goal for a particular joint by computing IK.
void constructRobotState(moveit_msgs::msg::RobotState &state)
Build a RobotState message for use with plan() or computeCartesianPath() If the move_group has a cust...
void setPlannerParams(const std::string &planner_id, const std::string &group, const std::map< std::string, std::string > ¶ms, bool bReplace=false)
Set the planner parameters for given group and planner_id.
void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
Specify the workspace bounding box. The box is specified in the planning frame (i....
const std::vector< std::string > & getJointModelGroupNames() const
Get the available planning group names.
static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
The name of the topic used by default for attached collision objects.
static const std::string EXECUTION_EVENT_TOPIC
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....
moveit_msgs::msg::Constraints mergeConstraints(const moveit_msgs::msg::Constraints &first, const moveit_msgs::msg::Constraints &second)
Merge two sets of constraints into one.
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.
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
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::core::RobotModelConstPtr getSharedRobotModel(const rclcpp::Node::SharedPtr &node, const std::string &robot_description)
std::shared_ptr< tf2_ros::Buffer > getSharedTF()
planning_scene_monitor::CurrentStateMonitorPtr getSharedStateMonitor(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &robot_model, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer)
getSharedStateMonitor
const std::string GRASP_PLANNING_SERVICE_NAME
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::Constraints >::ConstPtr ConstraintsWithMetadata
Main namespace for MoveIt.
This namespace includes the base class for MoveIt planners.
std::string append(const std::string &left, const std::string &right)
A set of options for the kinematics solver.
bool return_approximate_solution
Specification of options to use when constructing the MoveGroupInterface class.
std::string move_group_namespace
The namespace for the move group node.
std::string robot_description
The robot description parameter name (if different from default)
moveit::core::RobotModelConstPtr robot_model
Optionally, an instance of the RobotModel to use can be also specified.
std::string group_name
The group to construct the class instance for.
The representation of a motion plan (as ROS messages)