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 #if __has_include(<tf2/utils.hpp>)
66 #include <tf2/utils.hpp>
68 #include <tf2/utils.h>
70 #include <tf2_eigen/tf2_eigen.hpp>
71 #include <tf2_ros/transform_listener.h>
72 #include <rclcpp/rclcpp.hpp>
73 #include <rclcpp/version.h>
97 #if RCLCPP_VERSION_GTE(17, 0, 0)
100 return rclcpp::SystemDefaultsQoS();
105 return rmw_qos_profile_services_default;
117 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
const rclcpp::Duration& wait_for_servers)
118 : opt_(opt), node_(node), logger_(
moveit::
getLogger(
"moveit.ros.move_group_interface")), tf_buffer_(tf_buffer)
122 callback_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive,
124 callback_executor_.add_callback_group(callback_group_, node->get_node_base_interface());
125 callback_thread_ = std::thread([
this]() { callback_executor_.spin(); });
130 std::string error =
"Unable to construct robot model. Please make sure all needed information is on the "
132 RCLCPP_FATAL_STREAM(logger_, error);
133 throw std::runtime_error(error);
138 std::string error =
"Group '" + opt.
group_name +
"' was not found.";
139 RCLCPP_FATAL_STREAM(logger_, error);
140 throw std::runtime_error(error);
146 joint_state_target_ = std::make_shared<moveit::core::RobotState>(
getRobotModel());
147 joint_state_target_->setToDefaultValues();
148 active_target_ =
JOINT;
150 look_around_attempts_ = 0;
153 replan_attempts_ = 1;
154 goal_joint_tolerance_ = 1e-4;
155 goal_position_tolerance_ = 1e-4;
156 goal_orientation_tolerance_ = 1e-3;
157 allowed_planning_time_ = 5.0;
158 num_planning_attempts_ = 1;
159 node_->get_parameter_or<
double>(
"robot_description_planning.default_velocity_scaling_factor",
160 max_velocity_scaling_factor_, 0.1);
161 node_->get_parameter_or<
double>(
"robot_description_planning.default_acceleration_scaling_factor",
162 max_acceleration_scaling_factor_, 0.1);
163 initializing_constraints_ =
false;
165 if (joint_model_group_->
isChain())
169 trajectory_event_publisher_ = node_->create_publisher<std_msgs::msg::String>(
173 attached_object_publisher_ = node_->create_publisher<moveit_msgs::msg::AttachedCollisionObject>(
180 move_action_client_ = rclcpp_action::create_client<moveit_msgs::action::MoveGroup>(
182 move_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
183 execute_action_client_ = rclcpp_action::create_client<moveit_msgs::action::ExecuteTrajectory>(
185 execute_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
187 query_service_ = node_->create_client<moveit_msgs::srv::QueryPlannerInterfaces>(
190 get_params_service_ = node_->create_client<moveit_msgs::srv::GetPlannerParams>(
193 set_params_service_ = node_->create_client<moveit_msgs::srv::SetPlannerParams>(
196 cartesian_path_service_ = node_->create_client<moveit_msgs::srv::GetCartesianPath>(
200 RCLCPP_INFO_STREAM(logger_,
"Ready to take commands for planning group " << opt.
group_name <<
'.');
205 if (constraints_init_thread_)
206 constraints_init_thread_->join();
208 callback_executor_.cancel();
210 if (callback_thread_.joinable())
211 callback_thread_.join();
214 const std::shared_ptr<tf2_ros::Buffer>&
getTF()
const
231 return joint_model_group_;
236 return *move_action_client_;
241 auto req = std::make_shared<moveit_msgs::srv::QueryPlannerInterfaces::Request>();
242 auto future_response = query_service_->async_send_request(req);
244 if (future_response.valid())
246 const auto& response = future_response.get();
247 if (!response->planner_interfaces.empty())
249 desc = response->planner_interfaces.front();
258 auto req = std::make_shared<moveit_msgs::srv::QueryPlannerInterfaces::Request>();
259 auto future_response = query_service_->async_send_request(req);
260 if (future_response.valid())
262 const auto& response = future_response.get();
263 if (!response->planner_interfaces.empty())
265 desc = response->planner_interfaces;
272 std::map<std::string, std::string>
getPlannerParams(
const std::string& planner_id,
const std::string& group =
"")
274 auto req = std::make_shared<moveit_msgs::srv::GetPlannerParams::Request>();
275 moveit_msgs::srv::GetPlannerParams::Response::SharedPtr response;
276 req->planner_config = planner_id;
278 std::map<std::string, std::string> result;
280 auto future_response = get_params_service_->async_send_request(req);
281 if (future_response.valid())
283 response = future_response.get();
284 for (
unsigned int i = 0, end = response->params.keys.size(); i < end; ++i)
285 result[response->params.keys[i]] = response->params.values[i];
291 const std::map<std::string, std::string>& params,
bool replace =
false)
293 auto req = std::make_shared<moveit_msgs::srv::SetPlannerParams::Request>();
294 req->planner_config = planner_id;
296 req->replace = replace;
297 for (
const std::pair<const std::string, std::string>& param : params)
299 req->params.keys.push_back(param.first);
300 req->params.values.push_back(param.second);
302 set_params_service_->async_send_request(req);
307 std::string default_planning_pipeline;
308 node_->get_parameter(
"move_group.default_planning_pipeline", default_planning_pipeline);
309 return default_planning_pipeline;
314 if (pipeline_id != planning_pipeline_id_)
316 planning_pipeline_id_ = pipeline_id;
325 return planning_pipeline_id_;
332 if (!planning_pipeline_id_.empty())
333 pipeline_id = planning_pipeline_id_;
335 std::stringstream param_name;
336 param_name <<
"move_group";
337 if (!pipeline_id.empty())
338 param_name <<
"/planning_pipelines/" << pipeline_id;
340 param_name <<
'.' << group;
341 param_name <<
".default_planner_config";
343 std::string default_planner_config;
344 node_->get_parameter(param_name.str(), default_planner_config);
345 return default_planner_config;
350 planner_id_ = planner_id;
360 num_planning_attempts_ = num_planning_attempts;
370 return max_velocity_scaling_factor_;
375 setMaxScalingFactor(max_acceleration_scaling_factor_, value,
"acceleration_scaling_factor", 0.1);
380 return max_acceleration_scaling_factor_;
383 void setMaxScalingFactor(
double& variable,
const double target_value,
const char* factor_name,
double fallback_value)
385 if (target_value > 1.0)
387 RCLCPP_WARN(logger_,
"Limiting max_%s (%.2f) to 1.0.", factor_name, target_value);
390 else if (target_value <= 0.0)
392 node_->get_parameter_or<
double>(std::string(
"robot_description_planning.default_") + factor_name, variable,
394 if (target_value < 0.0)
396 RCLCPP_WARN(logger_,
"max_%s < 0.0! Setting to default: %.2f.", factor_name, variable);
401 variable = target_value;
407 return *joint_state_target_;
412 return *joint_state_target_;
417 considered_start_state_ = start_state;
422 considered_start_state_ = moveit_msgs::msg::RobotState();
429 considered_start_state_ = moveit_msgs::msg::RobotState();
430 considered_start_state_.is_diff =
true;
435 moveit::core::RobotStatePtr s;
442 const std::string& frame,
bool approx)
444 const std::string& eef = end_effector_link.empty() ?
getEndEffectorLink() : end_effector_link;
479 tf2::fromMsg(eef_pose, p);
485 RCLCPP_ERROR(logger_,
"Unable to transform from frame '%s' to frame '%s'", frame.c_str(),
497 end_effector_link_ = end_effector;
502 pose_targets_.erase(end_effector_link);
507 pose_targets_.clear();
512 return end_effector_link_;
517 if (!end_effector_link_.empty())
519 const std::vector<std::string>& possible_eefs =
521 for (
const std::string& possible_eef : possible_eefs)
527 static std::string empty;
531 bool setPoseTargets(
const std::vector<geometry_msgs::msg::PoseStamped>& poses,
const std::string& end_effector_link)
533 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
536 RCLCPP_ERROR(logger_,
"No end-effector to set the pose for");
541 pose_targets_[eef] = poses;
543 std::vector<geometry_msgs::msg::PoseStamped>& stored_poses = pose_targets_[eef];
544 for (geometry_msgs::msg::PoseStamped& stored_pose : stored_poses)
545 stored_pose.header.stamp = rclcpp::Time(0);
552 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
553 return pose_targets_.find(eef) != pose_targets_.end();
556 const geometry_msgs::msg::PoseStamped&
getPoseTarget(
const std::string& end_effector_link)
const
558 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
561 std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>>::const_iterator jt = pose_targets_.find(eef);
562 if (jt != pose_targets_.end())
564 if (!jt->second.empty())
565 return jt->second.at(0);
569 static const geometry_msgs::msg::PoseStamped UNKNOWN;
570 RCLCPP_ERROR(logger_,
"Pose for end-effector '%s' not known.", eef.c_str());
574 const std::vector<geometry_msgs::msg::PoseStamped>&
getPoseTargets(
const std::string& end_effector_link)
const
576 const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
578 std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>>::const_iterator jt = pose_targets_.find(eef);
579 if (jt != pose_targets_.end())
581 if (!jt->second.empty())
586 static const std::vector<geometry_msgs::msg::PoseStamped> EMPTY;
587 RCLCPP_ERROR(logger_,
"Poses for end-effector '%s' are not known.", eef.c_str());
593 pose_reference_frame_ = pose_reference_frame;
598 return pose_reference_frame_;
603 active_target_ = type;
608 return active_target_;
613 if (!current_state_monitor_)
615 RCLCPP_ERROR(logger_,
"Unable to monitor current robot state");
620 if (!current_state_monitor_->isActive())
621 current_state_monitor_->startStateMonitor();
623 current_state_monitor_->waitForCompleteState(opt_.
group_name, wait);
627 bool getCurrentState(moveit::core::RobotStatePtr& current_state,
double wait_seconds = 1.0)
629 if (!current_state_monitor_)
631 RCLCPP_ERROR(logger_,
"Unable to get current robot state");
636 if (!current_state_monitor_->isActive())
637 current_state_monitor_->startStateMonitor();
639 if (!current_state_monitor_->waitForCurrentState(node_->now(), wait_seconds))
641 RCLCPP_ERROR(logger_,
"Failed to fetch current robot state");
645 current_state = current_state_monitor_->getCurrentState();
651 if (!move_action_client_ || !move_action_client_->action_server_is_ready())
653 RCLCPP_INFO_STREAM(logger_,
"MoveGroup action client/server not ready");
654 return moveit::core::MoveItErrorCode::FAILURE;
656 RCLCPP_INFO_STREAM(logger_,
"MoveGroup action client/server ready");
658 moveit_msgs::action::MoveGroup::Goal goal;
660 goal.planning_options.plan_only =
true;
661 goal.planning_options.look_around =
false;
662 goal.planning_options.replan =
false;
663 goal.planning_options.planning_scene_diff.is_diff =
true;
664 goal.planning_options.planning_scene_diff.robot_state.is_diff =
true;
667 rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
668 std::shared_ptr<moveit_msgs::action::MoveGroup::Result> res;
669 auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::MoveGroup>::SendGoalOptions();
671 send_goal_opts.goal_response_callback =
672 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr& goal_handle) {
676 RCLCPP_INFO(logger_,
"Planning request rejected");
679 RCLCPP_INFO(logger_,
"Planning request accepted");
681 send_goal_opts.result_callback =
682 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::WrappedResult& result) {
689 case rclcpp_action::ResultCode::SUCCEEDED:
690 RCLCPP_INFO(logger_,
"Planning request complete!");
692 case rclcpp_action::ResultCode::ABORTED:
693 RCLCPP_INFO(logger_,
"Planning request aborted");
695 case rclcpp_action::ResultCode::CANCELED:
696 RCLCPP_INFO(logger_,
"Planning request canceled");
699 RCLCPP_INFO(logger_,
"Planning request unknown result code");
704 auto goal_handle_future = move_action_client_->async_send_goal(goal, send_goal_opts);
709 std::this_thread::sleep_for(std::chrono::milliseconds(1));
712 if (code != rclcpp_action::ResultCode::SUCCEEDED)
714 RCLCPP_ERROR_STREAM(logger_,
"MoveGroupInterface::plan() failed or timeout reached");
715 return res->error_code;
718 plan.trajectory = res->planned_trajectory;
719 plan.start_state = res->trajectory_start;
720 plan.planning_time = res->planning_time;
721 RCLCPP_INFO(logger_,
"time taken to generate plan: %g seconds",
plan.planning_time);
723 return res->error_code;
728 if (!move_action_client_ || !move_action_client_->action_server_is_ready())
730 RCLCPP_INFO_STREAM(logger_,
"MoveGroup action client/server not ready");
731 return moveit::core::MoveItErrorCode::FAILURE;
734 moveit_msgs::action::MoveGroup::Goal goal;
736 goal.planning_options.plan_only =
false;
737 goal.planning_options.look_around = can_look_;
738 goal.planning_options.replan = can_replan_;
739 goal.planning_options.replan_delay = replan_delay_;
740 goal.planning_options.planning_scene_diff.is_diff =
true;
741 goal.planning_options.planning_scene_diff.robot_state.is_diff =
true;
744 rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
745 std::shared_ptr<moveit_msgs::action::MoveGroup_Result> res;
746 auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::MoveGroup>::SendGoalOptions();
748 send_goal_opts.goal_response_callback =
749 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr& goal_handle) {
753 RCLCPP_INFO(logger_,
"Plan and Execute request rejected");
756 RCLCPP_INFO(logger_,
"Plan and Execute request accepted");
758 send_goal_opts.result_callback =
759 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::WrappedResult& result) {
766 case rclcpp_action::ResultCode::SUCCEEDED:
767 RCLCPP_INFO(logger_,
"Plan and Execute request complete!");
769 case rclcpp_action::ResultCode::ABORTED:
770 RCLCPP_INFO(logger_,
"Plan and Execute request aborted");
772 case rclcpp_action::ResultCode::CANCELED:
773 RCLCPP_INFO(logger_,
"Plan and Execute request canceled");
776 RCLCPP_INFO(logger_,
"Plan and Execute request unknown result code");
780 auto goal_handle_future = move_action_client_->async_send_goal(goal, send_goal_opts);
782 return moveit::core::MoveItErrorCode::SUCCESS;
787 std::this_thread::sleep_for(std::chrono::milliseconds(1));
790 if (code != rclcpp_action::ResultCode::SUCCEEDED)
792 RCLCPP_ERROR_STREAM(logger_,
"MoveGroupInterface::move() failed or timeout reached");
794 return res->error_code;
798 const std::vector<std::string>& controllers = std::vector<std::string>())
800 if (!execute_action_client_ || !execute_action_client_->action_server_is_ready())
802 RCLCPP_INFO_STREAM(logger_,
"execute_action_client_ client/server not ready");
803 return moveit::core::MoveItErrorCode::FAILURE;
807 rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN;
808 std::shared_ptr<moveit_msgs::action::ExecuteTrajectory_Result> res;
809 auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::ExecuteTrajectory>::SendGoalOptions();
811 send_goal_opts.goal_response_callback =
812 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::ExecuteTrajectory>::SharedPtr& goal_handle) {
816 RCLCPP_INFO(logger_,
"Execute request rejected");
819 RCLCPP_INFO(logger_,
"Execute request accepted");
821 send_goal_opts.result_callback =
822 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::ExecuteTrajectory>::WrappedResult& result) {
829 case rclcpp_action::ResultCode::SUCCEEDED:
830 RCLCPP_INFO(logger_,
"Execute request success!");
832 case rclcpp_action::ResultCode::ABORTED:
833 RCLCPP_INFO(logger_,
"Execute request aborted");
835 case rclcpp_action::ResultCode::CANCELED:
836 RCLCPP_INFO(logger_,
"Execute request canceled");
839 RCLCPP_INFO(logger_,
"Execute request unknown result code");
844 moveit_msgs::action::ExecuteTrajectory::Goal goal;
845 goal.trajectory = trajectory;
846 goal.controller_names = controllers;
848 auto goal_handle_future = execute_action_client_->async_send_goal(goal, send_goal_opts);
850 return moveit::core::MoveItErrorCode::SUCCESS;
855 std::this_thread::sleep_for(std::chrono::milliseconds(1));
858 if (code != rclcpp_action::ResultCode::SUCCEEDED)
860 RCLCPP_ERROR_STREAM(logger_,
"MoveGroupInterface::execute() failed or timeout reached");
862 return res->error_code;
866 moveit_msgs::msg::RobotTrajectory& msg,
867 const moveit_msgs::msg::Constraints& path_constraints,
bool avoid_collisions,
868 moveit_msgs::msg::MoveItErrorCodes& error_code)
870 auto req = std::make_shared<moveit_msgs::srv::GetCartesianPath::Request>();
871 moveit_msgs::srv::GetCartesianPath::Response::SharedPtr response;
873 req->start_state = considered_start_state_;
876 req->header.stamp =
getClock()->now();
877 req->waypoints = waypoints;
878 req->max_step = step;
879 req->path_constraints = path_constraints;
880 req->avoid_collisions = avoid_collisions;
882 req->max_velocity_scaling_factor = max_velocity_scaling_factor_;
883 req->max_acceleration_scaling_factor = max_acceleration_scaling_factor_;
885 auto future_response = cartesian_path_service_->async_send_request(req);
886 if (future_response.valid())
888 response = future_response.get();
889 error_code = response->error_code;
890 if (response->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
892 msg = response->solution;
893 return response->fraction;
900 error_code.val = error_code.FAILURE;
907 if (trajectory_event_publisher_)
909 std_msgs::msg::String event;
911 trajectory_event_publisher_->publish(event);
915 bool attachObject(
const std::string&
object,
const std::string& link,
const std::vector<std::string>& touch_links)
926 RCLCPP_ERROR(logger_,
"No known link to attach object '%s' to",
object.c_str());
929 moveit_msgs::msg::AttachedCollisionObject aco;
930 aco.object.id = object;
931 aco.link_name.swap(l);
932 if (touch_links.empty())
934 aco.touch_links.push_back(aco.link_name);
938 aco.touch_links = touch_links;
940 aco.object.operation = moveit_msgs::msg::CollisionObject::ADD;
941 attached_object_publisher_->publish(aco);
947 moveit_msgs::msg::AttachedCollisionObject aco;
951 aco.link_name =
name;
955 aco.object.id =
name;
957 aco.object.operation = moveit_msgs::msg::CollisionObject::REMOVE;
958 if (aco.link_name.empty() && aco.object.id.empty())
961 const std::vector<std::string>& lnames = joint_model_group_->
getLinkModelNames();
962 for (
const std::string& lname : lnames)
964 aco.link_name = lname;
965 attached_object_publisher_->publish(aco);
970 attached_object_publisher_->publish(aco);
977 return goal_position_tolerance_;
982 return goal_orientation_tolerance_;
987 return goal_joint_tolerance_;
992 goal_joint_tolerance_ = tolerance;
997 goal_position_tolerance_ = tolerance;
1002 goal_orientation_tolerance_ = tolerance;
1008 allowed_planning_time_ = seconds;
1013 return allowed_planning_time_;
1018 state = considered_start_state_;
1024 request.num_planning_attempts = num_planning_attempts_;
1025 request.max_velocity_scaling_factor = max_velocity_scaling_factor_;
1026 request.max_acceleration_scaling_factor = max_acceleration_scaling_factor_;
1027 request.allowed_planning_time = allowed_planning_time_;
1028 request.pipeline_id = planning_pipeline_id_;
1029 request.planner_id = planner_id_;
1030 request.workspace_parameters = workspace_parameters_;
1031 request.start_state = considered_start_state_;
1033 if (active_target_ ==
JOINT)
1035 request.goal_constraints.resize(1);
1039 else if (active_target_ == POSE || active_target_ ==
POSITION || active_target_ ==
ORIENTATION)
1042 std::size_t goal_count = 0;
1043 for (
const auto& pose_target : pose_targets_)
1044 goal_count = std::max(goal_count, pose_target.second.size());
1050 request.goal_constraints.resize(goal_count);
1052 for (
const auto& pose_target : pose_targets_)
1054 for (std::size_t i = 0; i < pose_target.second.size(); ++i)
1057 pose_target.first, pose_target.second[i], goal_position_tolerance_, goal_orientation_tolerance_);
1059 c.position_constraints.clear();
1061 c.orientation_constraints.clear();
1067 RCLCPP_ERROR(logger_,
"Unable to construct MotionPlanRequest representation");
1069 if (path_constraints_)
1070 request.path_constraints = *path_constraints_;
1071 if (trajectory_constraints_)
1072 request.trajectory_constraints = *trajectory_constraints_;
1082 path_constraints_ = std::make_unique<moveit_msgs::msg::Constraints>(constraint);
1087 if (constraints_storage_)
1090 if (constraints_storage_->getConstraints(msg_m, constraint, robot_model_->getName(), opt_.
group_name))
1093 std::make_unique<moveit_msgs::msg::Constraints>(
static_cast<moveit_msgs::msg::Constraints
>(*msg_m));
1105 path_constraints_.reset();
1110 trajectory_constraints_ = std::make_unique<moveit_msgs::msg::TrajectoryConstraints>(constraint);
1115 trajectory_constraints_.reset();
1120 while (initializing_constraints_)
1122 std::chrono::duration<double> d(0.01);
1123 rclcpp::sleep_for(std::chrono::duration_cast<std::chrono::nanoseconds>(d), rclcpp::Context::SharedPtr(
nullptr));
1126 std::vector<std::string> c;
1127 if (constraints_storage_)
1128 constraints_storage_->getKnownConstraints(c, robot_model_->getName(), opt_.
group_name);
1135 if (path_constraints_)
1137 return *path_constraints_;
1141 return moveit_msgs::msg::Constraints();
1147 if (trajectory_constraints_)
1149 return *trajectory_constraints_;
1153 return moveit_msgs::msg::TrajectoryConstraints();
1159 initializing_constraints_ =
true;
1160 if (constraints_init_thread_)
1161 constraints_init_thread_->join();
1162 constraints_init_thread_ =
1163 std::make_unique<std::thread>([
this, host, port] { initializeConstraintsStorageThread(host, port); });
1166 void setWorkspace(
double minx,
double miny,
double minz,
double maxx,
double maxy,
double maxz)
1168 workspace_parameters_.header.frame_id =
getRobotModel()->getModelFrame();
1169 workspace_parameters_.header.stamp =
getClock()->now();
1170 workspace_parameters_.min_corner.x = minx;
1171 workspace_parameters_.min_corner.y = miny;
1172 workspace_parameters_.min_corner.z = minz;
1173 workspace_parameters_.max_corner.x = maxx;
1174 workspace_parameters_.max_corner.y = maxy;
1175 workspace_parameters_.max_corner.z = maxz;
1180 return node_->get_clock();
1184 void initializeConstraintsStorageThread(
const std::string& host,
unsigned int port)
1190 conn->setParams(host, port);
1191 if (conn->connect())
1193 constraints_storage_ = std::make_unique<moveit_warehouse::ConstraintsStorage>(conn);
1196 catch (std::exception& ex)
1198 RCLCPP_ERROR(logger_,
"%s", ex.what());
1200 initializing_constraints_ =
false;
1204 rclcpp::Node::SharedPtr node_;
1205 rclcpp::Logger logger_;
1206 rclcpp::CallbackGroup::SharedPtr callback_group_;
1207 rclcpp::executors::SingleThreadedExecutor callback_executor_;
1208 std::thread callback_thread_;
1209 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
1210 moveit::core::RobotModelConstPtr robot_model_;
1211 planning_scene_monitor::CurrentStateMonitorPtr current_state_monitor_;
1213 std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::MoveGroup>> move_action_client_;
1216 std::shared_ptr<rclcpp_action::Client<moveit_msgs::action::ExecuteTrajectory>> execute_action_client_;
1219 moveit_msgs::msg::RobotState considered_start_state_;
1220 moveit_msgs::msg::WorkspaceParameters workspace_parameters_;
1221 double allowed_planning_time_;
1222 std::string planning_pipeline_id_;
1223 std::string planner_id_;
1224 unsigned int num_planning_attempts_;
1225 double max_velocity_scaling_factor_;
1226 double max_acceleration_scaling_factor_;
1227 double goal_joint_tolerance_;
1228 double goal_position_tolerance_;
1229 double goal_orientation_tolerance_;
1231 int32_t look_around_attempts_;
1233 int32_t replan_attempts_;
1234 double replan_delay_;
1237 moveit::core::RobotStatePtr joint_state_target_;
1242 std::map<std::string, std::vector<geometry_msgs::msg::PoseStamped>> pose_targets_;
1245 ActiveTargetType active_target_;
1246 std::unique_ptr<moveit_msgs::msg::Constraints> path_constraints_;
1247 std::unique_ptr<moveit_msgs::msg::TrajectoryConstraints> trajectory_constraints_;
1248 std::string end_effector_link_;
1249 std::string pose_reference_frame_;
1252 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr trajectory_event_publisher_;
1253 rclcpp::Publisher<moveit_msgs::msg::AttachedCollisionObject>::SharedPtr attached_object_publisher_;
1254 rclcpp::Client<moveit_msgs::srv::QueryPlannerInterfaces>::SharedPtr query_service_;
1255 rclcpp::Client<moveit_msgs::srv::GetPlannerParams>::SharedPtr get_params_service_;
1256 rclcpp::Client<moveit_msgs::srv::SetPlannerParams>::SharedPtr set_params_service_;
1257 rclcpp::Client<moveit_msgs::srv::GetCartesianPath>::SharedPtr cartesian_path_service_;
1259 std::unique_ptr<moveit_warehouse::ConstraintsStorage> constraints_storage_;
1260 std::unique_ptr<std::thread> constraints_init_thread_;
1261 bool initializing_constraints_;
1265 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
1266 const rclcpp::Duration& wait_for_servers)
1270 throw std::runtime_error(
"ROS does not seem to be running");
1276 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
1277 const rclcpp::Duration& wait_for_servers)
1289 : remembered_joint_values_(std::move(other.remembered_joint_values_))
1290 , impl_(other.impl_)
1291 , logger_(std::move(other.logger_))
1293 other.impl_ =
nullptr;
1301 impl_ = other.impl_;
1302 logger_ = other.logger_;
1303 remembered_joint_values_ = std::move(other.remembered_joint_values_);
1304 other.impl_ =
nullptr;
1324 return impl_->
getTF();
1343 const std::string& group)
const
1349 const std::map<std::string, std::string>& params,
bool replace)
1411 return impl_->
move(
false);
1421 return impl_->
move(
true);
1425 const std::vector<std::string>& controllers)
1427 return impl_->
execute(
plan.trajectory,
false, controllers);
1431 const std::vector<std::string>& controllers)
1433 return impl_->
execute(trajectory,
false, controllers);
1438 return impl_->
execute(
plan.trajectory,
true, controllers);
1442 const std::vector<std::string>& controllers)
1444 return impl_->
execute(trajectory,
true, controllers);
1453 moveit_msgs::msg::RobotTrajectory& trajectory,
bool avoid_collisions,
1454 moveit_msgs::msg::MoveItErrorCodes* error_code)
1456 moveit_msgs::msg::Constraints path_constraints_tmp;
1457 return computeCartesianPath(waypoints, eef_step, trajectory, moveit_msgs::msg::Constraints(), avoid_collisions,
1462 moveit_msgs::msg::RobotTrajectory& trajectory,
1463 const moveit_msgs::msg::Constraints& path_constraints,
1464 bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes* error_code)
1468 return impl_->
computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, *error_code);
1472 moveit_msgs::msg::MoveItErrorCodes err_tmp;
1473 err_tmp.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
1474 moveit_msgs::msg::MoveItErrorCodes& err = error_code ? *error_code : err_tmp;
1475 return impl_->
computeCartesianPath(waypoints, eef_step, trajectory, path_constraints, avoid_collisions, err);
1517 std::map<std::string, std::vector<double>>::const_iterator it = remembered_joint_values_.find(
name);
1518 std::map<std::string, double> positions;
1520 if (it != remembered_joint_values_.cend())
1523 for (
size_t x = 0; x < names.size(); ++x)
1525 positions[names[x]] = it->second[x];
1532 RCLCPP_ERROR(logger_,
"The requested named target '%s' does not exist, returning empty positions.",
name.c_str());
1540 std::map<std::string, std::vector<double>>::const_iterator it = remembered_joint_values_.find(
name);
1541 if (it != remembered_joint_values_.end())
1552 RCLCPP_ERROR(logger_,
"The requested named target '%s' does not exist",
name.c_str());
1565 if (joint_values.size() != n_group_joints)
1567 RCLCPP_DEBUG_STREAM(logger_,
"Provided joint value list has length " << joint_values.size() <<
" but group "
1569 <<
" has " << n_group_joints <<
" joints");
1580 for (
const auto& pair : variable_values)
1582 if (std::find(allowed.begin(), allowed.end(), pair.first) == allowed.end())
1584 RCLCPP_ERROR_STREAM(logger_,
"joint variable " << pair.first <<
" is not part of group "
1596 const std::vector<double>& variable_values)
1598 if (variable_names.size() != variable_values.size())
1600 RCLCPP_ERROR_STREAM(logger_,
"sizes of name and position arrays do not match");
1604 for (
const auto& variable_name : variable_names)
1606 if (std::find(allowed.begin(), allowed.end(), variable_name) == allowed.end())
1608 RCLCPP_ERROR_STREAM(logger_,
"joint variable " << variable_name <<
" is not part of group "
1628 std::vector<double> values(1, value);
1642 RCLCPP_ERROR_STREAM(logger_,
1653 const std::string& end_effector_link)
1659 const std::string& end_effector_link)
1661 return impl_->
setJointValueTarget(eef_pose.pose, end_effector_link, eef_pose.header.frame_id,
false);
1666 geometry_msgs::msg::Pose msg = tf2::toMsg(eef_pose);
1671 const std::string& end_effector_link)
1677 const std::string& end_effector_link)
1679 return impl_->
setJointValueTarget(eef_pose.pose, end_effector_link, eef_pose.header.frame_id,
true);
1683 const std::string& end_effector_link)
1685 geometry_msgs::msg::Pose msg = tf2::toMsg(eef_pose);
1733 std::vector<geometry_msgs::msg::PoseStamped> pose_msg(1);
1734 pose_msg[0].pose = tf2::toMsg(pose);
1736 pose_msg[0].header.stamp = impl_->
getClock()->now();
1742 std::vector<geometry_msgs::msg::PoseStamped> pose_msg(1);
1743 pose_msg[0].pose = target;
1745 pose_msg[0].header.stamp = impl_->
getClock()->now();
1750 const std::string& end_effector_link)
1752 std::vector<geometry_msgs::msg::PoseStamped> targets(1, target);
1758 std::vector<geometry_msgs::msg::PoseStamped> pose_out(target.size());
1759 rclcpp::Time tm = impl_->
getClock()->now();
1761 for (std::size_t i = 0; i < target.size(); ++i)
1763 pose_out[i].pose = tf2::toMsg(target[i]);
1764 pose_out[i].header.stamp = tm;
1765 pose_out[i].header.frame_id = frame_id;
1771 const std::string& end_effector_link)
1773 std::vector<geometry_msgs::msg::PoseStamped> target_stamped(target.size());
1774 rclcpp::Time tm = impl_->
getClock()->now();
1776 for (std::size_t i = 0; i < target.size(); ++i)
1778 target_stamped[i].pose = target[i];
1779 target_stamped[i].header.stamp = tm;
1780 target_stamped[i].header.frame_id = frame_id;
1786 const std::string& end_effector_link)
1790 RCLCPP_ERROR(logger_,
"No pose specified as goal target");
1805 const std::vector<geometry_msgs::msg::PoseStamped>&
1813 inline void transformPose(
const tf2_ros::Buffer& tf_buffer,
const std::string& desired_frame,
1814 geometry_msgs::msg::PoseStamped& target)
1816 if (desired_frame != target.header.frame_id)
1818 geometry_msgs::msg::PoseStamped target_in(target);
1819 tf_buffer.transform(target_in, target, desired_frame);
1821 target.header.stamp = rclcpp::Time(0);
1828 geometry_msgs::msg::PoseStamped target;
1836 target.pose.orientation.x = 0.0;
1837 target.pose.orientation.y = 0.0;
1838 target.pose.orientation.z = 0.0;
1839 target.pose.orientation.w = 1.0;
1843 target.pose.position.x = x;
1844 target.pose.position.y = y;
1845 target.pose.position.z = z;
1853 geometry_msgs::msg::PoseStamped target;
1861 target.pose.position.x = 0.0;
1862 target.pose.position.y = 0.0;
1863 target.pose.position.z = 0.0;
1868 target.pose.orientation = tf2::toMsg(q);
1875 const std::string& end_effector_link)
1877 geometry_msgs::msg::PoseStamped target;
1885 target.pose.position.x = 0.0;
1886 target.pose.position.y = 0.0;
1887 target.pose.position.z = 0.0;
1891 target.pose.orientation.x = x;
1892 target.pose.orientation.y = y;
1893 target.pose.orientation.z = z;
1894 target.pose.orientation.w = w;
1959 moveit::core::RobotStatePtr current_state;
1960 std::vector<double> values;
1962 current_state->copyJointGroupPositions(
getName(), values);
1968 std::vector<double> r;
1975 const std::string& eef = end_effector_link.empty() ?
getEndEffectorLink() : end_effector_link;
1976 Eigen::Isometry3d pose;
1980 RCLCPP_ERROR(logger_,
"No end-effector specified");
1984 moveit::core::RobotStatePtr current_state;
1990 pose = current_state->getGlobalLinkTransform(lm);
1993 geometry_msgs::msg::PoseStamped pose_msg;
1994 pose_msg.header.stamp = impl_->
getClock()->now();
1995 pose_msg.header.frame_id = impl_->
getRobotModel()->getModelFrame();
1996 pose_msg.pose = tf2::toMsg(pose);
2002 const std::string& eef = end_effector_link.empty() ?
getEndEffectorLink() : end_effector_link;
2003 Eigen::Isometry3d pose;
2007 RCLCPP_ERROR(logger_,
"No end-effector specified");
2011 moveit::core::RobotStatePtr current_state;
2016 pose = current_state->getGlobalLinkTransform(lm);
2019 geometry_msgs::msg::PoseStamped pose_msg;
2020 pose_msg.header.stamp = impl_->
getClock()->now();
2021 pose_msg.header.frame_id = impl_->
getRobotModel()->getModelFrame();
2022 pose_msg.pose = tf2::toMsg(pose);
2028 std::vector<double> result;
2029 const std::string& eef = end_effector_link.empty() ?
getEndEffectorLink() : end_effector_link;
2032 RCLCPP_ERROR(logger_,
"No end-effector specified");
2036 moveit::core::RobotStatePtr current_state;
2043 geometry_msgs::msg::TransformStamped tfs = tf2::eigenToTransform(current_state->getGlobalLinkTransform(lm));
2044 double pitch, roll, yaw;
2045 tf2::getEulerYPR<geometry_msgs::msg::Quaternion>(tfs.transform.rotation, yaw, pitch, roll);
2072 moveit::core::RobotStatePtr current_state;
2074 return current_state;
2079 remembered_joint_values_[
name] = values;
2084 remembered_joint_values_.erase(
name);
2089 impl_->can_look_ = flag;
2090 RCLCPP_DEBUG(logger_,
"Looking around: %s", flag ?
"yes" :
"no");
2097 RCLCPP_ERROR(logger_,
"Tried to set negative number of look-around attempts");
2101 RCLCPP_DEBUG_STREAM(logger_,
"Look around attempts: " << attempts);
2102 impl_->look_around_attempts_ = attempts;
2108 impl_->can_replan_ = flag;
2109 RCLCPP_DEBUG(logger_,
"Replanning: %s", flag ?
"yes" :
"no");
2116 RCLCPP_ERROR(logger_,
"Tried to set negative number of replan attempts");
2120 RCLCPP_DEBUG_STREAM(logger_,
"Replan Attempts: " << attempts);
2121 impl_->replan_attempts_ = attempts;
2129 RCLCPP_ERROR(logger_,
"Tried to set negative replan delay");
2133 RCLCPP_DEBUG_STREAM(logger_,
"Replan Delay: " << delay);
2134 impl_->replan_delay_ = delay;
2185 impl_->
setWorkspace(minx, miny, minz, maxx, maxy, maxz);
2202 return impl_->node_;
2217 return attachObject(
object, link, std::vector<std::string>());
2221 const std::vector<std::string>& touch_links)
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
bool isChain() const
Check if this group is a linear chain.
const std::string & getName() const
Get the name of the joint group.
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute random values for the state of the joint group.
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...
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 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 > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
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)
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...
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)
std::vector< std::string > getKnownConstraints() const
const std::string & getEndEffectorLink() const
bool startStateMonitor(double wait)
void setPlanningPipelineId(const std::string &pipeline_id)
const std::string & getEndEffector() const
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)
const Options & getOptions() const
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)
const std::string & getPlannerId() const
void setStartState(const moveit::core::RobotState &start_state)
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)
const moveit::core::RobotState & getTargetRobotState() const
bool getCurrentState(moveit::core::RobotStatePtr ¤t_state, double wait_seconds=1.0)
rclcpp_action::Client< moveit_msgs::action::MoveGroup > & getMoveGroupClient() 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)
void initializeConstraintsStorage(const std::string &host, unsigned int port)
void setPlannerId(const std::string &planner_id)
const std::shared_ptr< tf2_ros::Buffer > & getTF() const
double getGoalOrientationTolerance() const
moveit_msgs::msg::Constraints getPathConstraints() const
void setTargetType(ActiveTargetType type)
void setPathConstraints(const moveit_msgs::msg::Constraints &constraint)
std::map< std::string, std::string > getPlannerParams(const std::string &planner_id, const std::string &group="")
const moveit::core::JointModelGroup * getJointModelGroup() const
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)
void setNumPlanningAttempts(unsigned int num_planning_attempts)
const moveit::core::RobotModelConstPtr & getRobotModel() const
double getMaxVelocityScalingFactor() const
void setGoalJointTolerance(double tolerance)
const geometry_msgs::msg::PoseStamped & getPoseTarget(const std::string &end_effector_link) const
void setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints &constraint)
moveit::core::MoveItErrorCode move(bool wait)
void constructMotionPlanRequest(moveit_msgs::msg::MotionPlanRequest &request) const
void setPlanningTime(double seconds)
moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints() 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)
moveit::core::RobotState & getTargetRobotState()
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 std::string & getPlanningPipelineId() const
void setStartState(const moveit_msgs::msg::RobotState &start_state)
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()
const std::vector< geometry_msgs::msg::PoseStamped > & getPoseTargets(const std::string &end_effector_link) const
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::MoveItErrorCode plan(Plan &plan)
const std::string & getPoseReferenceFrame() 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)
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 ...
MoveGroupInterface & operator=(const MoveGroupInterface &)=delete
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
planning_interface::MotionPlanResponse plan(std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::shared_ptr< moveit_cpp::PlanningComponent::PlanRequestParameters > &single_plan_parameters, std::shared_ptr< moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters > &multi_plan_parameters, std::shared_ptr< planning_scene::PlanningScene > &planning_scene, std::optional< const moveit::planning_pipeline_interfaces::SolutionSelectionFunction > solution_selection_function, std::optional< moveit::planning_pipeline_interfaces::StoppingCriterionFunction > stopping_criterion_callback)
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.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
This namespace includes the base class for MoveIt planners.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
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)