50     return cmd.toRequest();
 
   69   moveit_msgs::msg::MotionSequenceRequest req;
 
   71   std::vector<std::string> group_names;
 
   72   for (
const auto& cmd : cmds_)
 
   74     moveit_msgs::msg::MotionSequenceItem item;
 
   77     if (std::find(group_names.begin(), group_names.end(), item.req.group_name) != group_names.end())
 
   81       item.req.start_state = moveit_msgs::msg::RobotState();
 
   85       group_names.emplace_back(item.req.group_name);
 
   88     item.blend_radius = cmd.second;
 
   89     req.items.push_back(item);
 
   96   const size_t orig_n{ 
size() };
 
   97   if (start > orig_n || end > orig_n)
 
  100     msg.append(
"Parameter start=").append(std::to_string(start));
 
  101     msg.append(
" and end=").append(std::to_string(end));
 
  102     msg.append(
" must not be greater then the number of #commands=");
 
  103     msg.append(std::to_string(
size()));
 
  104     throw std::invalid_argument(msg);
 
  106   cmds_.erase(cmds_.begin() + start, cmds_.begin() + end);
 
  110     cmds_.at(
size() - 1).second = 0.;
 
  116   return std::visit(
ToBaseVisitor(), cmds_.at(index_cmd).first);
 
Base class for commands storing all general information of a command.
 
size_t size() const
Returns the number of commands.
 
T & getCmd(const size_t index_cmd)
 
void erase(const size_t start, const size_t end)
Deletes all commands from index 'start' to index 'end'.
 
moveit_msgs::msg::MotionSequenceRequest toRequest() const
 
Visitor returning not the specific command type but the base type.
 
MotionCmd & operator()(T &cmd) const
 
Visitor transforming the stored command into a MotionPlanRequest.
 
planning_interface::MotionPlanRequest operator()(T &cmd) const
 
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest