38 #include <boost/variant.hpp>
45 class ToReqVisitor :
public boost::static_visitor<planning_interface::MotionPlanRequest>
51 return cmd.toRequest();
58 class ToBaseVisitor :
public boost::static_visitor<MotionCmd&>
70 moveit_msgs::MotionSequenceRequest req;
72 std::vector<std::string> group_names;
73 for (
const auto& cmd :
cmds_)
75 moveit_msgs::MotionSequenceItem item;
76 item.req = boost::apply_visitor(ToReqVisitor(),
cmd.first);
78 if (std::find(group_names.begin(), group_names.end(), item.req.group_name) != group_names.end())
82 item.req.start_state = moveit_msgs::RobotState();
86 group_names.emplace_back(item.req.group_name);
89 item.blend_radius =
cmd.second;
90 req.items.push_back(item);
97 const size_t orig_n{
size() };
98 if (
start > orig_n || end > orig_n)
101 msg.append(
"Parameter start=").append(std::to_string(start));
102 msg.append(
" and end=").append(std::to_string(end));
103 msg.append(
" must not be greater then the number of #commands=");
104 msg.append(std::to_string(
size()));
105 throw std::invalid_argument(msg);