42#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
53#include <moveit_msgs/action/execute_trajectory.hpp>
54#include <moveit_msgs/srv/query_planner_interfaces.hpp>
55#include <moveit_msgs/srv/get_cartesian_path.hpp>
56#include <moveit_msgs/srv/grasp_planning.hpp>
57#include <moveit_msgs/srv/get_planner_params.hpp>
58#include <moveit_msgs/srv/set_planner_params.hpp>
62#include <std_msgs/msg/string.hpp>
63#include <geometry_msgs/msg/transform_stamped.hpp>
65#include <tf2_eigen/tf2_eigen.hpp>
66#include <tf2_ros/transform_listener.h>
67#include <rclcpp/rclcpp.hpp>
68#include <rclcpp/version.h>
92#if RCLCPP_VERSION_GTE(17, 0, 0)
95 return rclcpp::SystemDefaultsQoS();
100 return rmw_qos_profile_services_default;
112 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
const rclcpp::Duration& wait_for_servers)
113 : opt_(opt), node_(node), logger_(
moveit::getLogger(
"moveit.ros.move_group_interface")), tf_buffer_(tf_buffer)
117 callback_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive,
119 callback_executor_.add_callback_group(callback_group_, node->get_node_base_interface());
120 callback_thread_ = std::thread([
this]() { callback_executor_.spin(); });
125 std::string error =
"Unable to construct robot model. Please make sure all needed information is on the "
127 RCLCPP_FATAL_STREAM(logger_, error);
128 throw std::runtime_error(error);
133 std::string error =
"Group '" + opt.
group_name +
"' was not found.";
134 RCLCPP_FATAL_STREAM(logger_, error);
135 throw std::runtime_error(error);
140 joint_state_target_ = std::make_shared<moveit::core::RobotState>(
getRobotModel());
141 joint_state_target_->setToDefaultValues();
142 active_target_ = JOINT;
144 look_around_attempts_ = 0;
147 replan_attempts_ = 1;
148 goal_joint_tolerance_ = 1e-4;
149 goal_position_tolerance_ = 1e-4;
150 goal_orientation_tolerance_ = 1e-3;
151 allowed_planning_time_ = 5.0;
152 num_planning_attempts_ = 1;
153 node_->get_parameter_or<
double>(
"robot_description_planning.default_velocity_scaling_factor",
154 max_velocity_scaling_factor_, 0.1);
155 node_->get_parameter_or<
double>(
"robot_description_planning.default_acceleration_scaling_factor",
156 max_acceleration_scaling_factor_, 0.1);
157 initializing_constraints_ =
false;
159 if (joint_model_group_->
isChain())
163 trajectory_event_publisher_ = node_->create_publisher<std_msgs::msg::String>(
167 attached_object_publisher_ = node_->create_publisher<moveit_msgs::msg::AttachedCollisionObject>(
174 move_action_client_ = rclcpp_action::create_client<moveit_msgs::action::MoveGroup>(
176 move_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
177 execute_action_client_ = rclcpp_action::create_client<moveit_msgs::action::ExecuteTrajectory>(
179 execute_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
181 query_service_ = node_->create_client<moveit_msgs::srv::QueryPlannerInterfaces>(
184 get_params_service_ = node_->create_client<moveit_msgs::srv::GetPlannerParams>(
187 set_params_service_ = node_->create_client<moveit_msgs::srv::SetPlannerParams>(
190 cartesian_path_service_ = node_->create_client<moveit_msgs::srv::GetCartesianPath>(
194 RCLCPP_INFO_STREAM(logger_,
"Ready to take commands for planning group " << opt.
group_name <<
'.');
199 if (constraints_init_thread_)
200 constraints_init_thread_->join();
202 callback_executor_.cancel();
204 if (callback_thread_.joinable())
205 callback_thread_.join();
208 const std::shared_ptr<tf2_ros::Buffer>&
getTF()
const
225 return joint_model_group_;
230 return *move_action_client_;
235 auto req = std::make_shared<moveit_msgs::srv::QueryPlannerInterfaces::Request>();
236 auto future_response = query_service_->async_send_request(req);
238 if (future_response.valid())
240 const auto& response = future_response.get();
241 if (!response->planner_interfaces.empty())
243 desc = response->planner_interfaces.front();
252 auto req = std::make_shared<moveit_msgs::srv::QueryPlannerInterfaces::Request>();
253 auto future_response = query_service_->async_send_request(req);
254 if (future_response.valid())
256 const auto& response = future_response.get();
257 if (!response->planner_interfaces.empty())
259 desc = response->planner_interfaces;
266 std::map<std::string, std::string>
getPlannerParams(
const std::string& planner_id,
const std::string& group =
"")
268 auto req = std::make_shared<moveit_msgs::srv::GetPlannerParams::Request>();
269 moveit_msgs::srv::GetPlannerParams::Response::SharedPtr response;
270 req->planner_config = planner_id;
272 std::map<std::string, std::string> result;
274 auto future_response = get_params_service_->async_send_request(req);
275 if (future_response.valid())
277 response = future_response.get();
278 for (
unsigned int i = 0, end = response->params.keys.size(); i < end; ++i)
279 result[response->params.keys[i]] = response->params.values[i];
285 const std::map<std::string, std::string>& params,
bool replace =
false)
287 auto req = std::make_shared<moveit_msgs::srv::SetPlannerParams::Request>();
288 req->planner_config = planner_id;
290 req->replace = replace;
291 for (
const std::pair<const std::string, std::string>& param : params)
293 req->params.keys.push_back(param.first);
294 req->params.values.push_back(param.second);
296 set_params_service_->async_send_request(req);
301 std::string default_planning_pipeline;
302 node_->get_parameter(
"move_group.default_planning_pipeline", default_planning_pipeline);
303 return default_planning_pipeline;
308 if (pipeline_id != planning_pipeline_id_)
310 planning_pipeline_id_ = pipeline_id;
319 return planning_pipeline_id_;
326 if (!planning_pipeline_id_.empty())
327 pipeline_id = planning_pipeline_id_;
329 std::stringstream param_name;
330 param_name <<
"move_group";
331 if (!pipeline_id.empty())
332 param_name <<
"/planning_pipelines/" << pipeline_id;
334 param_name <<
'.' << group;
335 param_name <<
".default_planner_config";
337 std::string default_planner_config;
338 node_->get_parameter(param_name.str(), default_planner_config);
339 return default_planner_config;
344 planner_id_ = planner_id;
354 num_planning_attempts_ = num_planning_attempts;
364 return max_velocity_scaling_factor_;
369 setMaxScalingFactor(max_acceleration_scaling_factor_, value,
"acceleration_scaling_factor", 0.1);
374 return max_acceleration_scaling_factor_;
377 void setMaxScalingFactor(
double& variable,
const double target_value,
const char* factor_name,
double fallback_value)
379 if (target_value > 1.0)
381 RCLCPP_WARN(logger_,
"Limiting max_%s (%.2f) to 1.0.", factor_name, target_value);
384 else if (target_value <= 0.0)
386 node_->get_parameter_or<
double>(std::string(
"robot_description_planning.default_") + factor_name, variable,
388 if (target_value < 0.0)
390 RCLCPP_WARN(logger_,
"max_%s < 0.0! Setting to default: %.2f.", factor_name, variable);
395 variable = target_value;
401 return *joint_state_target_;
406 return *joint_state_target_;
411 considered_start_state_ = std::make_shared<moveit::core::RobotState>(start_state);
416 considered_start_state_.reset();
421 if (considered_start_state_)
423 return considered_start_state_;
427 moveit::core::RobotStatePtr s;
434 const std::string& frame,
bool approx)
436 const std::string& eef = end_effector_link.empty() ?
getEndEffectorLink() : end_effector_link;
471 tf2::fromMsg(eef_pose, p);
477 RCLCPP_ERROR(logger_,
"Unable to transform from frame '%s' to frame '%s'", frame.c_str(),
489 end_effector_link_ = end_effector;
494 pose_targets_.erase(end_effector_link);
499 pose_targets_.clear();
504 return end_effector_link_;
509 if (!end_effector_link_.empty())
511 const std::vector<std::string>& possible_eefs =
513 for (
const std::string& possible_eef : possible_eefs)
515 if (
getRobotModel()->getEndEffector(possible_eef)->hasLinkModel(end_effector_link_))
519 static std::string empty;
523 bool setPoseTargets(
const std::vector<geometry_msgs::msg::PoseStamped>& poses,
const std::string& end_effector_link)
525 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
528 RCLCPP_ERROR(logger_,
"No end-effector to set the pose for");
533 pose_targets_[eef] = poses;
535 std::vector<geometry_msgs::msg::PoseStamped>& stored_poses = pose_targets_[eef];
536 for (geometry_msgs::msg::PoseStamped& stored_pose : stored_poses)
537 stored_pose.header.stamp = rclcpp::Time(0);
544 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
545 return pose_targets_.find(eef) != pose_targets_.end();
548 const geometry_msgs::msg::PoseStamped&
getPoseTarget(
const std::string& end_effector_link)
const
550 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
553 std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>>::const_iterator jt = pose_targets_.find(eef);
554 if (jt != pose_targets_.end())
556 if (!jt->second.empty())
557 return jt->second.at(0);
561 static const geometry_msgs::msg::PoseStamped UNKNOWN;
562 RCLCPP_ERROR(logger_,
"Pose for end-effector '%s' not known.", eef.c_str());
566 const std::vector<geometry_msgs::msg::PoseStamped>&
getPoseTargets(
const std::string& end_effector_link)
const
568 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
570 std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>>::const_iterator jt = pose_targets_.find(eef);
571 if (jt != pose_targets_.end())
573 if (!jt->second.empty())
578 static const std::vector<geometry_msgs::msg::PoseStamped> EMPTY;
579 RCLCPP_ERROR(logger_,
"Poses for end-effector '%s' are not known.", eef.c_str());
585 pose_reference_frame_ = pose_reference_frame;
590 support_surface_ = support_surface;
595 return pose_reference_frame_;
600 active_target_ = type;
605 return active_target_;
610 if (!current_state_monitor_)
612 RCLCPP_ERROR(logger_,
"Unable to monitor current robot state");
617 if (!current_state_monitor_->isActive())
618 current_state_monitor_->startStateMonitor();
620 current_state_monitor_->waitForCompleteState(opt_.
group_name, wait);
624 bool getCurrentState(moveit::core::RobotStatePtr& current_state,
double wait_seconds = 1.0)
626 if (!current_state_monitor_)
628 RCLCPP_ERROR(logger_,
"Unable to get current robot state");
633 if (!current_state_monitor_->isActive())
634 current_state_monitor_->startStateMonitor();
636 if (!current_state_monitor_->waitForCurrentState(node_->now(), wait_seconds))
638 RCLCPP_ERROR(logger_,
"Failed to fetch current robot state");
642 current_state = current_state_monitor_->getCurrentState();
648 if (!move_action_client_ || !move_action_client_->action_server_is_ready())
650 RCLCPP_INFO_STREAM(logger_,
"MoveGroup action client/server not ready");
651 return moveit::core::MoveItErrorCode::FAILURE;
653 RCLCPP_INFO_STREAM(logger_,
"MoveGroup action client/server ready");
655 moveit_msgs::action::MoveGroup::Goal goal;
657 goal.planning_options.plan_only =
true;
658 goal.planning_options.look_around =
false;
659 goal.planning_options.replan =
false;
660 goal.planning_options.planning_scene_diff.is_diff =
true;
661 goal.planning_options.planning_scene_diff.robot_state.is_diff =
true;
664 rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
665 std::shared_ptr<moveit_msgs::action::MoveGroup::Result> res;
666 auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::MoveGroup>::SendGoalOptions();
668 send_goal_opts.goal_response_callback =
669 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr& goal_handle) {
673 RCLCPP_INFO(logger_,
"Planning request rejected");
676 RCLCPP_INFO(logger_,
"Planning request accepted");
678 send_goal_opts.result_callback =
679 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::WrappedResult& result) {
686 case rclcpp_action::ResultCode::SUCCEEDED:
687 RCLCPP_INFO(logger_,
"Planning request complete!");
689 case rclcpp_action::ResultCode::ABORTED:
690 RCLCPP_INFO(logger_,
"Planning request aborted");
692 case rclcpp_action::ResultCode::CANCELED:
693 RCLCPP_INFO(logger_,
"Planning request canceled");
696 RCLCPP_INFO(logger_,
"Planning request unknown result code");
701 auto goal_handle_future = move_action_client_->async_send_goal(goal, send_goal_opts);
706 std::this_thread::sleep_for(std::chrono::milliseconds(1));
709 if (code != rclcpp_action::ResultCode::SUCCEEDED)
711 RCLCPP_ERROR_STREAM(logger_,
"MoveGroupInterface::plan() failed or timeout reached");
712 return res->error_code;
715 plan.trajectory = res->planned_trajectory;
716 plan.start_state = res->trajectory_start;
717 plan.planning_time = res->planning_time;
718 RCLCPP_INFO(logger_,
"time taken to generate plan: %g seconds",
plan.planning_time);
720 return res->error_code;
725 if (!move_action_client_ || !move_action_client_->action_server_is_ready())
727 RCLCPP_INFO_STREAM(logger_,
"MoveGroup action client/server not ready");
728 return moveit::core::MoveItErrorCode::FAILURE;
731 moveit_msgs::action::MoveGroup::Goal goal;
733 goal.planning_options.plan_only =
false;
734 goal.planning_options.look_around = can_look_;
735 goal.planning_options.replan = can_replan_;
736 goal.planning_options.replan_delay = replan_delay_;
737 goal.planning_options.planning_scene_diff.is_diff =
true;
738 goal.planning_options.planning_scene_diff.robot_state.is_diff =
true;
741 rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
742 std::shared_ptr<moveit_msgs::action::MoveGroup_Result> res;
743 auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::MoveGroup>::SendGoalOptions();
745 send_goal_opts.goal_response_callback =
746 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr& goal_handle) {
750 RCLCPP_INFO(logger_,
"Plan and Execute request rejected");
753 RCLCPP_INFO(logger_,
"Plan and Execute request accepted");
755 send_goal_opts.result_callback =
756 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::WrappedResult& result) {
763 case rclcpp_action::ResultCode::SUCCEEDED:
764 RCLCPP_INFO(logger_,
"Plan and Execute request complete!");
766 case rclcpp_action::ResultCode::ABORTED:
767 RCLCPP_INFO(logger_,
"Plan and Execute request aborted");
769 case rclcpp_action::ResultCode::CANCELED:
770 RCLCPP_INFO(logger_,
"Plan and Execute request canceled");
773 RCLCPP_INFO(logger_,
"Plan and Execute request unknown result code");
777 auto goal_handle_future = move_action_client_->async_send_goal(goal, send_goal_opts);
779 return moveit::core::MoveItErrorCode::SUCCESS;
784 std::this_thread::sleep_for(std::chrono::milliseconds(1));
787 if (code != rclcpp_action::ResultCode::SUCCEEDED)
789 RCLCPP_ERROR_STREAM(logger_,
"MoveGroupInterface::move() failed or timeout reached");
791 return res->error_code;
795 const std::vector<std::string>& controllers = std::vector<std::string>())
797 if (!execute_action_client_ || !execute_action_client_->action_server_is_ready())
799 RCLCPP_INFO_STREAM(logger_,
"execute_action_client_ client/server not ready");
800 return moveit::core::MoveItErrorCode::FAILURE;
804 rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
805 std::shared_ptr<moveit_msgs::action::ExecuteTrajectory_Result> res;
806 auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::ExecuteTrajectory>::SendGoalOptions();
808 send_goal_opts.goal_response_callback =
809 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::ExecuteTrajectory>::SharedPtr& goal_handle) {
813 RCLCPP_INFO(logger_,
"Execute request rejected");
816 RCLCPP_INFO(logger_,
"Execute request accepted");
818 send_goal_opts.result_callback =
819 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::ExecuteTrajectory>::WrappedResult& result) {
826 case rclcpp_action::ResultCode::SUCCEEDED:
827 RCLCPP_INFO(logger_,
"Execute request success!");
829 case rclcpp_action::ResultCode::ABORTED:
830 RCLCPP_INFO(logger_,
"Execute request aborted");
832 case rclcpp_action::ResultCode::CANCELED:
833 RCLCPP_INFO(logger_,
"Execute request canceled");
836 RCLCPP_INFO(logger_,
"Execute request unknown result code");
841 moveit_msgs::action::ExecuteTrajectory::Goal goal;
842 goal.trajectory = trajectory;
843 goal.controller_names = controllers;
845 auto goal_handle_future = execute_action_client_->async_send_goal(goal, send_goal_opts);
847 return moveit::core::MoveItErrorCode::SUCCESS;
852 std::this_thread::sleep_for(std::chrono::milliseconds(1));
855 if (code != rclcpp_action::ResultCode::SUCCEEDED)
857 RCLCPP_ERROR_STREAM(logger_,
"MoveGroupInterface::execute() failed or timeout reached");
859 return res->error_code;
863 moveit_msgs::msg::RobotTrajectory& msg,
864 const moveit_msgs::msg::Constraints& path_constraints,
bool avoid_collisions,
865 moveit_msgs::msg::MoveItErrorCodes& error_code)
867 auto req = std::make_shared<moveit_msgs::srv::GetCartesianPath::Request>();
868 moveit_msgs::srv::GetCartesianPath::Response::SharedPtr response;
874 req->header.stamp =
getClock()->now();
875 req->waypoints = waypoints;
876 req->max_step = step;
877 req->path_constraints = path_constraints;
878 req->avoid_collisions = avoid_collisions;
880 req->max_velocity_scaling_factor = max_velocity_scaling_factor_;
881 req->max_acceleration_scaling_factor = max_acceleration_scaling_factor_;
883 auto future_response = cartesian_path_service_->async_send_request(req);
884 if (future_response.valid())
886 response = future_response.get();
887 error_code = response->error_code;
888 if (response->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
890 msg = response->solution;
891 return response->fraction;
898 error_code.val = error_code.FAILURE;
905 if (trajectory_event_publisher_)
907 std_msgs::msg::String event;
909 trajectory_event_publisher_->publish(event);
913 bool attachObject(
const std::string&
object,
const std::string& link,
const std::vector<std::string>& touch_links)
924 RCLCPP_ERROR(logger_,
"No known link to attach object '%s' to",
object.c_str());
927 moveit_msgs::msg::AttachedCollisionObject aco;
928 aco.object.id = object;
929 aco.link_name.swap(l);
930 if (touch_links.empty())
932 aco.touch_links.push_back(aco.link_name);
936 aco.touch_links = touch_links;
938 aco.object.operation = moveit_msgs::msg::CollisionObject::ADD;
939 attached_object_publisher_->publish(aco);
945 moveit_msgs::msg::AttachedCollisionObject aco;
947 if (!name.empty() && joint_model_group_->
hasLinkModel(name))
949 aco.link_name = name;
953 aco.object.id = name;
955 aco.object.operation = moveit_msgs::msg::CollisionObject::REMOVE;
956 if (aco.link_name.empty() && aco.object.id.empty())
959 const std::vector<std::string>& lnames = joint_model_group_->
getLinkModelNames();
960 for (
const std::string& lname : lnames)
962 aco.link_name = lname;
963 attached_object_publisher_->publish(aco);
968 attached_object_publisher_->publish(aco);
975 return goal_position_tolerance_;
980 return goal_orientation_tolerance_;
985 return goal_joint_tolerance_;
990 goal_joint_tolerance_ = tolerance;
995 goal_position_tolerance_ = tolerance;
1000 goal_orientation_tolerance_ = tolerance;
1006 allowed_planning_time_ = seconds;
1011 return allowed_planning_time_;
1016 if (considered_start_state_)
1022 state.is_diff =
true;
1029 request.num_planning_attempts = num_planning_attempts_;
1030 request.max_velocity_scaling_factor = max_velocity_scaling_factor_;
1031 request.max_acceleration_scaling_factor = max_acceleration_scaling_factor_;
1032 request.allowed_planning_time = allowed_planning_time_;
1033 request.pipeline_id = planning_pipeline_id_;
1034 request.planner_id = planner_id_;
1035 request.workspace_parameters = workspace_parameters_;
1039 if (active_target_ == JOINT)
1041 request.goal_constraints.resize(1);
1045 else if (active_target_ == POSE || active_target_ == POSITION || active_target_ == ORIENTATION)
1048 std::size_t goal_count = 0;
1049 for (
const auto& pose_target : pose_targets_)
1050 goal_count = std::max(goal_count, pose_target.second.size());
1056 request.goal_constraints.resize(goal_count);
1058 for (
const auto& pose_target : pose_targets_)
1060 for (std::size_t i = 0; i < pose_target.second.size(); ++i)
1063 pose_target.first, pose_target.second[i], goal_position_tolerance_, goal_orientation_tolerance_);
1064 if (active_target_ == ORIENTATION)
1065 c.position_constraints.clear();
1066 if (active_target_ == POSITION)
1067 c.orientation_constraints.clear();
1073 RCLCPP_ERROR(logger_,
"Unable to construct MotionPlanRequest representation");
1075 if (path_constraints_)
1076 request.path_constraints = *path_constraints_;
1077 if (trajectory_constraints_)
1078 request.trajectory_constraints = *trajectory_constraints_;
1143 path_constraints_ = std::make_unique<moveit_msgs::msg::Constraints>(constraint);
1148 if (constraints_storage_)
1151 if (constraints_storage_->getConstraints(msg_m, constraint, robot_model_->getName(), opt_.
group_name))
1154 std::make_unique<moveit_msgs::msg::Constraints>(
static_cast<moveit_msgs::msg::Constraints
>(*msg_m));
1166 path_constraints_.reset();
1171 trajectory_constraints_ = std::make_unique<moveit_msgs::msg::TrajectoryConstraints>(constraint);
1176 trajectory_constraints_.reset();
1181 while (initializing_constraints_)
1183 std::chrono::duration<double> d(0.01);
1184 rclcpp::sleep_for(std::chrono::duration_cast<std::chrono::nanoseconds>(d), rclcpp::Context::SharedPtr(
nullptr));
1187 std::vector<std::string> c;
1188 if (constraints_storage_)
1189 constraints_storage_->getKnownConstraints(c, robot_model_->getName(), opt_.
group_name);
1196 if (path_constraints_)
1198 return *path_constraints_;
1202 return moveit_msgs::msg::Constraints();
1208 if (trajectory_constraints_)
1210 return *trajectory_constraints_;
1214 return moveit_msgs::msg::TrajectoryConstraints();
1220 initializing_constraints_ =
true;
1221 if (constraints_init_thread_)
1222 constraints_init_thread_->join();
1223 constraints_init_thread_ =
1224 std::make_unique<std::thread>([
this, host, port] { initializeConstraintsStorageThread(host, port); });
1227 void setWorkspace(
double minx,
double miny,
double minz,
double maxx,
double maxy,
double maxz)
1229 workspace_parameters_.header.frame_id =
getRobotModel()->getModelFrame();
1230 workspace_parameters_.header.stamp =
getClock()->now();
1231 workspace_parameters_.min_corner.x = minx;
1232 workspace_parameters_.min_corner.y = miny;
1233 workspace_parameters_.min_corner.z = minz;
1234 workspace_parameters_.max_corner.x = maxx;
1235 workspace_parameters_.max_corner.y = maxy;
1236 workspace_parameters_.max_corner.z = maxz;
1241 return node_->get_clock();
1245 void initializeConstraintsStorageThread(
const std::string& host,
unsigned int port)
1251 conn->setParams(host, port);
1252 if (conn->connect())
1254 constraints_storage_ = std::make_unique<moveit_warehouse::ConstraintsStorage>(conn);
1257 catch (std::exception& ex)
1259 RCLCPP_ERROR(logger_,
"%s", ex.what());
1261 initializing_constraints_ =
false;
1265 rclcpp::Node::SharedPtr node_;
1266 rclcpp::Logger logger_;
1267 rclcpp::CallbackGroup::SharedPtr callback_group_;
1268 rclcpp::executors::SingleThreadedExecutor callback_executor_;
1269 std::thread callback_thread_;
1270 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
1271 moveit::core::RobotModelConstPtr robot_model_;
1272 planning_scene_monitor::CurrentStateMonitorPtr current_state_monitor_;
1274 std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::MoveGroup>> move_action_client_;
1277 std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::ExecuteTrajectory>> execute_action_client_;
1280 moveit::core::RobotStatePtr considered_start_state_;
1281 moveit_msgs::msg::WorkspaceParameters workspace_parameters_;
1282 double allowed_planning_time_;
1283 std::string planning_pipeline_id_;
1284 std::string planner_id_;
1285 unsigned int num_planning_attempts_;
1286 double max_velocity_scaling_factor_;
1287 double max_acceleration_scaling_factor_;
1288 double goal_joint_tolerance_;
1289 double goal_position_tolerance_;
1290 double goal_orientation_tolerance_;
1292 int32_t look_around_attempts_;
1294 int32_t replan_attempts_;
1295 double replan_delay_;
1298 moveit::core::RobotStatePtr joint_state_target_;
1303 std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>> pose_targets_;
1306 ActiveTargetType active_target_;
1307 std::unique_ptr<moveit_msgs::msg::Constraints> path_constraints_;
1308 std::unique_ptr<moveit_msgs::msg::TrajectoryConstraints> trajectory_constraints_;
1309 std::string end_effector_link_;
1310 std::string pose_reference_frame_;
1311 std::string support_surface_;
1314 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr trajectory_event_publisher_;
1315 rclcpp::Publisher<moveit_msgs::msg::AttachedCollisionObject>::SharedPtr attached_object_publisher_;
1316 rclcpp::Client<moveit_msgs::srv::QueryPlannerInterfaces>::SharedPtr query_service_;
1317 rclcpp::Client<moveit_msgs::srv::GetPlannerParams>::SharedPtr get_params_service_;
1318 rclcpp::Client<moveit_msgs::srv::SetPlannerParams>::SharedPtr set_params_service_;
1319 rclcpp::Client<moveit_msgs::srv::GetCartesianPath>::SharedPtr cartesian_path_service_;
1321 std::unique_ptr<moveit_warehouse::ConstraintsStorage> constraints_storage_;
1322 std::unique_ptr<std::thread> constraints_init_thread_;
1323 bool initializing_constraints_;
1327 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
1328 const rclcpp::Duration& wait_for_servers)
1329 : logger_(
moveit::getLogger(
"moveit.ros.move_group_interface"))
1332 throw std::runtime_error(
"ROS does not seem to be running");
1338 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
1339 const rclcpp::Duration& wait_for_servers)
1340 : logger_(
moveit::getLogger(
"moveit.ros.move_group_interface"))
1351 : remembered_joint_values_(std::move(other.remembered_joint_values_))
1352 , impl_(other.impl_)
1353 , logger_(std::move(other.logger_))
1355 other.impl_ =
nullptr;
1363 impl_ = other.impl_;
1364 logger_ = other.logger_;
1365 remembered_joint_values_ = std::move(other.remembered_joint_values_);
1366 other.impl_ =
nullptr;
1386 return impl_->
getTF();
1405 const std::string& group)
const
1411 const std::map<std::string, std::string>& params,
bool replace)
1473 return impl_->
move(
false);
1483 return impl_->
move(
true);
1487 const std::vector<std::string>& controllers)
1489 return impl_->
execute(
plan.trajectory,
false, controllers);
1493 const std::vector<std::string>& controllers)
1495 return impl_->
execute(trajectory,
false, controllers);
1500 return impl_->
execute(
plan.trajectory,
true, controllers);
1504 const std::vector<std::string>& controllers)
1506 return impl_->
execute(trajectory,
true, controllers);
1555 moveit_msgs::msg::RobotTrajectory& trajectory,
bool avoid_collisions,
1556 moveit_msgs::msg::MoveItErrorCodes* error_code)
1558 moveit_msgs::msg::Constraints path_constraints_tmp;
1559 return computeCartesianPath(waypoints, eef_step, trajectory, moveit_msgs::msg::Constraints(), avoid_collisions,
1564 moveit_msgs::msg::RobotTrajectory& trajectory,
1565 const moveit_msgs::msg::Constraints& path_constraints,
1566 bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes* error_code)
1570 return impl_->
computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, *error_code);
1574 moveit_msgs::msg::MoveItErrorCodes err_tmp;
1575 err_tmp.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
1576 moveit_msgs::msg::MoveItErrorCodes& err = error_code ? *error_code : err_tmp;
1577 return impl_->
computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, err);
1588 moveit::core::RobotStatePtr rs;
1589 if (start_state.is_diff)
1595 rs = std::make_shared<moveit::core::RobotState>(
getRobotModel());
1596 rs->setToDefaultValues();
1630 std::map<std::string, std::vector<double>>::const_iterator it = remembered_joint_values_.find(name);
1631 std::map<std::string, double> positions;
1633 if (it != remembered_joint_values_.cend())
1636 for (
size_t x = 0; x < names.size(); ++x)
1638 positions[names[x]] = it->second[x];
1645 RCLCPP_ERROR(logger_,
"The requested named target '%s' does not exist, returning empty positions.", name.c_str());
1653 std::map<std::string, std::vector<double>>::const_iterator it = remembered_joint_values_.find(name);
1654 if (it != remembered_joint_values_.end())
1665 RCLCPP_ERROR(logger_,
"The requested named target '%s' does not exist", name.c_str());
1678 if (joint_values.size() != n_group_joints)
1680 RCLCPP_DEBUG_STREAM(logger_,
"Provided joint value list has length " << joint_values.size() <<
" but group "
1682 <<
" has " << n_group_joints <<
" joints");
1693 for (
const auto& pair : variable_values)
1695 if (std::find(allowed.begin(), allowed.end(), pair.first) == allowed.end())
1697 RCLCPP_ERROR_STREAM(logger_,
"joint variable " << pair.first <<
" is not part of group "
1709 const std::vector<double>& variable_values)
1711 if (variable_names.size() != variable_values.size())
1713 RCLCPP_ERROR_STREAM(logger_,
"sizes of name and position arrays do not match");
1717 for (
const auto& variable_name : variable_names)
1719 if (std::find(allowed.begin(), allowed.end(), variable_name) == allowed.end())
1721 RCLCPP_ERROR_STREAM(logger_,
"joint variable " << variable_name <<
" is not part of group "
1741 std::vector<double> values(1, value);
1755 RCLCPP_ERROR_STREAM(logger_,
1766 const std::string& end_effector_link)
1772 const std::string& end_effector_link)
1774 return impl_->
setJointValueTarget(eef_pose.pose, end_effector_link, eef_pose.header.frame_id,
false);
1779 geometry_msgs::msg::Pose msg = tf2::toMsg(eef_pose);
1784 const std::string& end_effector_link)
1790 const std::string& end_effector_link)
1792 return impl_->
setJointValueTarget(eef_pose.pose, end_effector_link, eef_pose.header.frame_id,
true);
1796 const std::string& end_effector_link)
1798 geometry_msgs::msg::Pose msg = tf2::toMsg(eef_pose);
1846 std::vector<geometry_msgs::msg::PoseStamped> pose_msg(1);
1847 pose_msg[0].pose = tf2::toMsg(pose);
1849 pose_msg[0].header.stamp = impl_->
getClock()->now();
1855 std::vector<geometry_msgs::msg::PoseStamped> pose_msg(1);
1856 pose_msg[0].pose = target;
1858 pose_msg[0].header.stamp = impl_->
getClock()->now();
1863 const std::string& end_effector_link)
1865 std::vector<geometry_msgs::msg::PoseStamped> targets(1, target);
1871 std::vector<geometry_msgs::msg::PoseStamped> pose_out(target.size());
1872 rclcpp::Time tm = impl_->
getClock()->now();
1874 for (std::size_t i = 0; i < target.size(); ++i)
1876 pose_out[i].pose = tf2::toMsg(target[i]);
1877 pose_out[i].header.stamp = tm;
1878 pose_out[i].header.frame_id = frame_id;
1884 const std::string& end_effector_link)
1886 std::vector<geometry_msgs::msg::PoseStamped> target_stamped(target.size());
1887 rclcpp::Time tm = impl_->
getClock()->now();
1889 for (std::size_t i = 0; i < target.size(); ++i)
1891 target_stamped[i].pose = target[i];
1892 target_stamped[i].header.stamp = tm;
1893 target_stamped[i].header.frame_id = frame_id;
1899 const std::string& end_effector_link)
1903 RCLCPP_ERROR(logger_,
"No pose specified as goal target");
1918const std::vector<geometry_msgs::msg::PoseStamped>&
1926inline void transformPose(
const tf2_ros::Buffer& tf_buffer,
const std::string& desired_frame,
1927 geometry_msgs::msg::PoseStamped& target)
1929 if (desired_frame != target.header.frame_id)
1931 geometry_msgs::msg::PoseStamped target_in(target);
1932 tf_buffer.transform(target_in, target, desired_frame);
1934 target.header.stamp = rclcpp::Time(0);
1941 geometry_msgs::msg::PoseStamped target;
1949 target.pose.orientation.x = 0.0;
1950 target.pose.orientation.y = 0.0;
1951 target.pose.orientation.z = 0.0;
1952 target.pose.orientation.w = 1.0;
1956 target.pose.position.x = x;
1957 target.pose.position.y = y;
1958 target.pose.position.z = z;
1966 geometry_msgs::msg::PoseStamped target;
1974 target.pose.position.x = 0.0;
1975 target.pose.position.y = 0.0;
1976 target.pose.position.z = 0.0;
1981 target.pose.orientation = tf2::toMsg(q);
1988 const std::string& end_effector_link)
1990 geometry_msgs::msg::PoseStamped target;
1998 target.pose.position.x = 0.0;
1999 target.pose.position.y = 0.0;
2000 target.pose.position.z = 0.0;
2004 target.pose.orientation.x = x;
2005 target.pose.orientation.y = y;
2006 target.pose.orientation.z = z;
2007 target.pose.orientation.w = w;
2072 moveit::core::RobotStatePtr current_state;
2073 std::vector<double> values;
2075 current_state->copyJointGroupPositions(
getName(), values);
2081 std::vector<double> r;
2088 const std::string& eef = end_effector_link.empty() ?
getEndEffectorLink() : end_effector_link;
2089 Eigen::Isometry3d pose;
2093 RCLCPP_ERROR(logger_,
"No end-effector specified");
2097 moveit::core::RobotStatePtr current_state;
2103 pose = current_state->getGlobalLinkTransform(lm);
2106 geometry_msgs::msg::PoseStamped pose_msg;
2107 pose_msg.header.stamp = impl_->
getClock()->now();
2108 pose_msg.header.frame_id = impl_->
getRobotModel()->getModelFrame();
2109 pose_msg.pose = tf2::toMsg(pose);
2115 const std::string& eef = end_effector_link.empty() ?
getEndEffectorLink() : end_effector_link;
2116 Eigen::Isometry3d pose;
2120 RCLCPP_ERROR(logger_,
"No end-effector specified");
2124 moveit::core::RobotStatePtr current_state;
2129 pose = current_state->getGlobalLinkTransform(lm);
2132 geometry_msgs::msg::PoseStamped pose_msg;
2133 pose_msg.header.stamp = impl_->
getClock()->now();
2134 pose_msg.header.frame_id = impl_->
getRobotModel()->getModelFrame();
2135 pose_msg.pose = tf2::toMsg(pose);
2141 std::vector<double> result;
2142 const std::string& eef = end_effector_link.empty() ?
getEndEffectorLink() : end_effector_link;
2145 RCLCPP_ERROR(logger_,
"No end-effector specified");
2149 moveit::core::RobotStatePtr current_state;
2156 geometry_msgs::msg::TransformStamped tfs = tf2::eigenToTransform(current_state->getGlobalLinkTransform(lm));
2157 double pitch, roll, yaw;
2158 tf2::getEulerYPR<geometry_msgs::msg::Quaternion>(tfs.transform.rotation, yaw, pitch, roll);
2185 moveit::core::RobotStatePtr current_state;
2187 return current_state;
2192 remembered_joint_values_[name] = values;
2197 remembered_joint_values_.erase(name);
2202 impl_->can_look_ = flag;
2203 RCLCPP_DEBUG(logger_,
"Looking around: %s", flag ?
"yes" :
"no");
2210 RCLCPP_ERROR(logger_,
"Tried to set negative number of look-around attempts");
2214 RCLCPP_DEBUG_STREAM(logger_,
"Look around attempts: " << attempts);
2215 impl_->look_around_attempts_ = attempts;
2221 impl_->can_replan_ = flag;
2222 RCLCPP_DEBUG(logger_,
"Replanning: %s", flag ?
"yes" :
"no");
2229 RCLCPP_ERROR(logger_,
"Tried to set negative number of replan attempts");
2233 RCLCPP_DEBUG_STREAM(logger_,
"Replan Attempts: " << attempts);
2234 impl_->replan_attempts_ = attempts;
2242 RCLCPP_ERROR(logger_,
"Tried to set negative replan delay");
2246 RCLCPP_DEBUG_STREAM(logger_,
"Replan Delay: " << delay);
2247 impl_->replan_delay_ = delay;
2298 impl_->
setWorkspace(minx, miny, minz, maxx, maxy, maxz);
2320 return impl_->node_;
2335 return attachObject(
object, link, std::vector<std::string>());
2339 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)
void setSupportSurfaceName(const std::string &support_surface)
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
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).
void setSupportSurfaceName(const std::string &name)
For pick/place operations, the name of the support surface is used to specify the fact that attached ...
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)