ceti_robot.h
Go to the documentation of this file.
1 #ifndef CETI_ROBOT_
2 #define CETI_ROBOT_
3 
4 #include "ros/ros.h"
5 #include "robot/abstract_robot.h"
9 
11 
14 class CetiRobot : public AbstractRobot{
15  protected:
16  std::vector<std::unique_ptr<AbstractRobotElementDecorator>> observers_;
17  std::bitset<3> observer_mask_;
18 
19 
20  public:
22 
28  CetiRobot(std::string& name, tf2::Transform tf, tf2::Vector3 size);
29 
30 
31 
32  std::string& name() override {return name_;}
33  tf2::Transform& tf() override {return tf_;}
34  tf2::Vector3& size() override {return size_;}
35  tf2::Transform& rootTf() override {return root_tf_;}
36  std::vector<tf2::Transform>& bounds() override {return bounds_;}
37  std::vector<tf2::Transform>& robotRootBounds() override {return robot_root_bounds_;}
38 
40 
43  inline void setObservers(std::vector<std::unique_ptr<AbstractRobotElementDecorator>>& observer) {
44  for (int i = 0; i < observer.size();i++){
45  observers_.push_back(std::move(observer[i]));
46  }
47  }
48 
50 
53  inline std::vector<std::unique_ptr<AbstractRobotElementDecorator>>& observers() { return observers_;}
54 
56  void reset();
57 
59 
64  bool inCollision(CetiRobot* R);
65 
67 
74  bool checkSingleObjectCollision(tf2::Transform& obj, std::string& robot_element, std::bitset<3>& panel_mask) override;
75 
77 
80  void notify() override;
81 
82  inline std::bitset<3> observerMask() {return observer_mask_;}
83  inline void setObserverMask(int i) {observer_mask_ = std::bitset<3>(i);}
84 
85 
86 
87 };
88 
89 
90 
91 
92 #endif
CetiRobot::observers
std::vector< std::unique_ptr< AbstractRobotElementDecorator > > & observers()
Get observers.
Definition: ceti_robot.h:53
CetiRobot::inCollision
bool inCollision(CetiRobot *R)
Collsion calculation.
Definition: ceti_robot.cpp:73
CetiRobot::setObserverMask
void setObserverMask(int i)
Definition: ceti_robot.h:83
CetiRobot::observers_
std::vector< std::unique_ptr< AbstractRobotElementDecorator > > observers_
Wing shared pointers.
Definition: ceti_robot.h:16
CetiRobot::setObservers
void setObservers(std::vector< std::unique_ptr< AbstractRobotElementDecorator >> &observer)
Set observers.
Definition: ceti_robot.h:43
abstract_robot.h
AbstractRobot::bounds_
std::vector< tf2::Transform > bounds_
Bounds of table top surface.
Definition: abstract_robot.h:31
CetiRobot::notify
void notify() override
Observer pattern.
Definition: ceti_robot.cpp:68
CetiRobot::observer_mask_
std::bitset< 3 > observer_mask_
Bitmap to set observers.
Definition: ceti_robot.h:17
CetiRobot::reset
void reset()
Resset all robot properties.
Definition: ceti_robot.cpp:63
AbstractRobot::root_tf_
tf2::Transform root_tf_
Robot root on table top.
Definition: abstract_robot.h:30
CetiRobot::rootTf
tf2::Transform & rootTf() override
Definition: ceti_robot.h:35
AbstractRobot
Abstract Robot implementation.
Definition: abstract_robot.h:25
CetiRobot::CetiRobot
CetiRobot(std::string &name, tf2::Transform tf, tf2::Vector3 size)
Ceti robot constructor.
Definition: ceti_robot.cpp:4
CetiRobot::observerMask
std::bitset< 3 > observerMask()
Definition: ceti_robot.h:82
CetiRobot::size
tf2::Vector3 & size() override
Definition: ceti_robot.h:34
CetiRobot
Concrete Ceti-Robot.
Definition: ceti_robot.h:14
CetiRobot::bounds
std::vector< tf2::Transform > & bounds() override
Definition: ceti_robot.h:36
CetiRobot::checkSingleObjectCollision
bool checkSingleObjectCollision(tf2::Transform &obj, std::string &robot_element, std::bitset< 3 > &panel_mask) override
Collsion calculation for single objects.
Definition: ceti_robot.cpp:10
AbstractRobot::tf_
tf2::Transform tf_
Pose of table.
Definition: abstract_robot.h:29
CetiRobot::name
std::string & name() override
Definition: ceti_robot.h:32
abstract_robot_element_decorator.h
CetiRobot::robotRootBounds
std::vector< tf2::Transform > & robotRootBounds() override
Definition: ceti_robot.h:37
CetiRobot::tf
tf2::Transform & tf() override
Definition: ceti_robot.h:33
panel.h
AbstractRobot::name_
std::string name_
Name of robot.
Definition: abstract_robot.h:27
abstract_robot_element.h
AbstractRobot::size_
tf2::Vector3 size_
Size of table.
Definition: abstract_robot.h:28
AbstractRobot::robot_root_bounds_
std::vector< tf2::Transform > robot_root_bounds_
Bounds of robot arm as sub-region of table top.
Definition: abstract_robot.h:32


multi_cell_builder
Author(s): Matteo Anedda
autogenerated on Sun Apr 9 2023 23:59:51