42 #include <type_traits>
43 #include <initializer_list>
45 #include <Eigen/Geometry>
47 #include <moveit/macros/class_forward.h>
49 namespace planning_scene {
50 MOVEIT_CLASS_FORWARD(PlanningScene);
56 MOVEIT_CLASS_FORWARD(LinkModel);
57 MOVEIT_CLASS_FORWARD(JointModelGroup);
58 MOVEIT_CLASS_FORWARD(RobotState);
61 namespace task_constructor {
62 MOVEIT_CLASS_FORWARD(Property);
67 template <
typename Enum>
70 static_assert((
sizeof(Enum) <=
sizeof(
int)),
"Flags uses an int as storage, this enum will overflow!");
73 using Int =
typename std::conditional<std::is_unsigned<Enum>::value,
unsigned int,
int>::type;
74 using enum_type = Enum;
78 constexpr
inline Flags() noexcept : i(Int(0)) {}
80 constexpr
inline Flags(Enum f) noexcept : i(Int(f)) {}
82 constexpr
inline Flags(std::initializer_list<Enum> flags) noexcept
83 : i(initializer_list_helper(flags.begin(), flags.end())) {}
85 const inline Flags& operator&=(
int mask) noexcept {
89 const inline Flags& operator&=(
unsigned int mask) noexcept {
93 const inline Flags& operator&=(Enum mask) noexcept {
97 const inline Flags& operator|=(
Flags f) noexcept {
101 const inline Flags& operator|=(Enum f) noexcept {
105 const inline Flags& operator^=(
Flags f) noexcept {
109 const inline Flags& operator^=(Enum f) noexcept {
114 constexpr
inline operator Int()
const noexcept {
return i; }
116 constexpr
inline Flags operator|(
Flags f)
const noexcept {
return Flags(i | f.i); }
117 constexpr
inline Flags operator|(Enum f)
const noexcept {
return Flags(i | Int(f)); }
118 constexpr
inline Flags operator^(
Flags f)
const noexcept {
return Flags(i ^ f.i); }
119 constexpr
inline Flags operator^(Enum f)
const noexcept {
return Flags(i ^ Int(f)); }
120 constexpr
inline Flags operator&(
int mask)
const noexcept {
return Flags(i & mask); }
121 constexpr
inline Flags operator&(
unsigned int mask)
const noexcept {
return Flags(i & mask); }
122 constexpr
inline Flags operator&(Enum f)
const noexcept {
return Flags(i & Int(f)); }
123 constexpr
inline Flags operator~()
const noexcept {
return Flags(~i); }
125 constexpr
inline bool operator!()
const noexcept {
return !i; }
127 constexpr
inline bool testFlag(Enum f)
const noexcept {
128 return (i & Int(f)) == Int(f) && (Int(f) != 0 || i == Int(f));
132 constexpr
inline Flags(Int i) : i(i) {}
133 constexpr
static inline Int
134 initializer_list_helper(
typename std::initializer_list<Enum>::const_iterator it,
135 typename std::initializer_list<Enum>::const_iterator end) noexcept {
136 return (it == end ? Int(0) : (Int(*it) | initializer_list_helper(it + 1, end)));
142 bool getRobotTipForFrame(
const Property& property,
const planning_scene::PlanningScene& scene,
143 const moveit::core::JointModelGroup* jmg, std::string& error_msg,
144 const moveit::core::LinkModel*& robot_link, Eigen::Isometry3d& tip_in_global_frame);
Definition: properties.h:70