sequence.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019 Pilz GmbH & Co. KG
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
19 #include <algorithm>
20 #include <boost/variant.hpp>
21 
23 {
27 class ToReqVisitor : public boost::static_visitor<planning_interface::MotionPlanRequest>
28 {
29 public:
30  template <typename T>
32  {
33  return cmd.toRequest();
34  }
35 };
36 
40 class ToBaseVisitor : public boost::static_visitor<MotionCmd&>
41 {
42 public:
43  template <typename T>
44  MotionCmd& operator()(T& cmd) const
45  {
46  return cmd;
47  }
48 };
49 
50 pilz_msgs::MotionSequenceRequest Sequence::toRequest() const
51 {
52  pilz_msgs::MotionSequenceRequest req;
53 
54  std::vector<std::string> group_names;
55  for (const auto& cmd : cmds_)
56  {
57  pilz_msgs::MotionSequenceItem item;
58  item.req = boost::apply_visitor(ToReqVisitor(), cmd.first);
59 
60  if (std::find(group_names.begin(), group_names.end(), item.req.group_name) != group_names.end())
61  {
62  // Remove start state because only the first request of a group
63  // is allowed to have a start state in a sequence.
64  item.req.start_state = moveit_msgs::RobotState();
65  }
66  else
67  {
68  group_names.emplace_back(item.req.group_name);
69  }
70 
71  item.blend_radius = cmd.second;
72  req.items.push_back(item);
73  }
74  return req;
75 }
76 
77 void Sequence::erase(const size_t start, const size_t end)
78 {
79  const size_t orig_n{ size() };
80  if (start > orig_n || end > orig_n)
81  {
82  std::string msg;
83  msg.append("Parameter start=").append(std::to_string(start));
84  msg.append(" and end=").append(std::to_string(end));
85  msg.append(" must not be greater then the number of #commands=");
86  msg.append(std::to_string(size()));
87  throw std::invalid_argument(msg);
88  }
89  cmds_.erase(cmds_.begin() + start, cmds_.begin() + end);
90  if (end == orig_n)
91  {
92  // Make sure last radius is set zero
93  cmds_.at(size() - 1).second = 0.;
94  }
95 }
96 
97 MotionCmd& Sequence::getCmd(const size_t index_cmd)
98 {
99  return boost::apply_visitor(ToBaseVisitor(), cmds_.at(index_cmd).first);
100 }
101 
102 } // namespace pilz_industrial_motion_testutils
Visitor transforming the stored command into a MotionPlanRequest.
Definition: sequence.cpp:27
string cmd
Base class for commands storing all general information of a command.
Definition: motioncmd.h:30
std::size_t size(custom_string const &s)
void erase(const size_t start, const size_t end)
Deletes all commands from index &#39;start&#39; to index &#39;end&#39;.
Definition: sequence.cpp:77
T & getCmd(const size_t index_cmd)
Definition: sequence.h:96
planning_interface::MotionPlanRequest operator()(T &cmd) const
Definition: sequence.cpp:31
moveit_msgs::MotionPlanRequest MotionPlanRequest
pilz_msgs::MotionSequenceRequest toRequest() const
Definition: sequence.cpp:50
Visitor returning not the specific command type but the base type.
Definition: sequence.cpp:40


pilz_industrial_motion_testutils
Author(s):
autogenerated on Mon Feb 28 2022 23:13:36