sequence.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019 Pilz GmbH & Co. KG
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Pilz GmbH & Co. KG nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 
37 #include <algorithm>
38 #include <boost/variant.hpp>
39 
41 {
45 class ToReqVisitor : public boost::static_visitor<planning_interface::MotionPlanRequest>
46 {
47 public:
48  template <typename T>
50  {
51  return cmd.toRequest();
52  }
53 };
54 
58 class ToBaseVisitor : public boost::static_visitor<MotionCmd&>
59 {
60 public:
61  template <typename T>
62  MotionCmd& operator()(T& cmd) const
63  {
64  return cmd;
65  }
66 };
67 
68 moveit_msgs::MotionSequenceRequest Sequence::toRequest() const
69 {
70  moveit_msgs::MotionSequenceRequest req;
71 
72  std::vector<std::string> group_names;
73  for (const auto& cmd : cmds_)
74  {
75  moveit_msgs::MotionSequenceItem item;
76  item.req = boost::apply_visitor(ToReqVisitor(), cmd.first);
77 
78  if (std::find(group_names.begin(), group_names.end(), item.req.group_name) != group_names.end())
79  {
80  // Remove start state because only the first request of a group
81  // is allowed to have a start state in a sequence.
82  item.req.start_state = moveit_msgs::RobotState();
83  }
84  else
85  {
86  group_names.emplace_back(item.req.group_name);
87  }
88 
89  item.blend_radius = cmd.second;
90  req.items.push_back(item);
91  }
92  return req;
93 }
94 
95 void Sequence::erase(const size_t start, const size_t end)
96 {
97  const size_t orig_n{ size() };
98  if (start > orig_n || end > orig_n)
99  {
100  std::string msg;
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);
106  }
107  cmds_.erase(cmds_.begin() + start, cmds_.begin() + end);
108  if (end == orig_n)
109  {
110  // Make sure last radius is set zero
111  cmds_.at(size() - 1).second = 0.;
112  }
113 }
114 
115 MotionCmd& Sequence::getCmd(const size_t index_cmd)
116 {
117  return boost::apply_visitor(ToBaseVisitor(), cmds_.at(index_cmd).first);
118 }
119 
120 } // namespace pilz_industrial_motion_planner_testutils
pilz_industrial_motion_planner_testutils::MotionCmd
Base class for commands storing all general information of a command.
Definition: motioncmd.h:80
pilz_industrial_motion_planner_testutils::ToBaseVisitor::operator()
MotionCmd & operator()(T &cmd) const
Definition: sequence.cpp:94
pilz_industrial_motion_planner_testutils::ToReqVisitor::operator()
planning_interface::MotionPlanRequest operator()(T &cmd) const
Definition: sequence.cpp:113
pilz_industrial_motion_planner_testutils::Sequence::toRequest
moveit_msgs::MotionSequenceRequest toRequest() const
Definition: sequence.cpp:100
pilz_industrial_motion_planner_testutils::Sequence::size
size_t size() const
Returns the number of commands.
Definition: sequence.h:140
sequence.h
pilz_industrial_motion_planner_testutils::ToBaseVisitor
Visitor returning not the specific command type but the base type.
Definition: sequence.cpp:90
pilz_industrial_motion_planner_testutils
Definition: basecmd.h:42
pilz_industrial_motion_planner_testutils::Sequence::getCmd
T & getCmd(const size_t index_cmd)
Definition: sequence.h:146
pilz_industrial_motion_planner_testutils::Sequence::erase
void erase(const size_t start, const size_t end)
Deletes all commands from index 'start' to index 'end'.
Definition: sequence.cpp:127
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
start
ROSCPP_DECL void start()
cmd
string cmd
pilz_industrial_motion_planner_testutils::Sequence::cmds_
std::vector< TCmdRadiiPair > cmds_
Definition: sequence.h:164


pilz_industrial_motion_planner_testutils
Author(s):
autogenerated on Sat May 3 2025 02:28:27