pose.hpp
Go to the documentation of this file.
1 #ifndef FANUC_POST_PROCESSOR_POSE_HPP
2 #define FANUC_POST_PROCESSOR_POSE_HPP
3 
4 #include <Eigen/Dense>
6 #include <ros/ros.h>
7 #include <tuple>
8 
9 namespace fanuc_post_processor
10 {
11 
12 class FanucPose
13 {
14 public:
19  {
21  };
22 
26  enum SpeedType
27  {
29  };
30 
34  enum class FlipNonFlip
35  {
36  Flip,
37  NonFlip
38  };
39 
43  enum class Elbow
44  {
45  Up,
46  Down
47  };
48 
52  enum class BackFront
53  {
54  Back,
55  Front
56  };
57 
61  typedef std::tuple<FlipNonFlip, Elbow, BackFront> Config;
62 
63 private:
64  std::string
65  movementTypeToString() const;
66 
67  std::string
68  speedTypeToString() const;
69 
70  std::string
71  configurationToString() const;
72 
73 public:
74 
80  FanucPose(const std::vector<FanucAxis> extended_axes = {},
81  const std::vector<FanucGroup> extra_groups = {});
82 
83  virtual ~FanucPose();
84 
92  bool hasSameGroupsAxes(const FanucPose &other) const;
93 
98  bool isValid() const;
99 
103  std::string getMainLineString() const;
104 
108  std::string getPoseLinesString() const;
109 
114  void setRobotPose(const Eigen::Isometry3d &pose);
115 
116  // If true: this pose is only a duplicate of an existing pose in the program
117  // The existence will be verified when adding the pose
118  bool is_pose_id_ = false;
119  unsigned pose_id_ = 1; // Unique within a Fanuc program. Cannot be zero
120  MovementType move_type_ = MovementType::LINEAR;
121  double speed_ = 10;
122  SpeedType speed_type_ = SpeedType::CM_MIN;
123  // CNT = 0 == Fine
124  // CNT 1-100 is smooth motion
125  unsigned cnt_ = 100;
126  bool speed_register_ = false; // If true, speed will be converted to unsigned and used as a register number
129  std::vector<FanucGroup> groups_;
130  std::string option_; // Time before, time after, offset PR etc...
131 };
132 
133 }
134 
135 #endif
Definition: axis.hpp:6
bool speed_register_
Definition: pose.hpp:126
FlipNonFlip
Definition: pose.hpp:34
unsigned cnt_
Definition: pose.hpp:125
std::string movementTypeToString() const
Definition: pose.cpp:39
FanucPose(const std::vector< FanucAxis > extended_axes={}, const std::vector< FanucGroup > extra_groups={})
Definition: pose.cpp:6
MovementType
Definition: pose.hpp:18
Definition: pose.hpp:28
Definition: pose.hpp:28
Definition: pose.hpp:12
BackFront
Definition: pose.hpp:52
virtual ~FanucPose()
Definition: pose.cpp:35
Config configuration_
Definition: pose.hpp:127
bool isValid() const
Definition: pose.cpp:113
Definition: pose.hpp:28
Definition: pose.hpp:28
Elbow
Definition: pose.hpp:43
Definition: pose.hpp:28
unsigned pose_id_
Definition: pose.hpp:119
std::vector< FanucGroup > groups_
Definition: pose.hpp:129
Definition: pose.hpp:28
std::string configurationToString() const
Definition: pose.cpp:69
std::string speedTypeToString() const
Definition: pose.cpp:49
double speed_
Definition: pose.hpp:121
std::string getMainLineString() const
Definition: pose.cpp:242
Definition: pose.hpp:20
std::string option_
Definition: pose.hpp:130
unsigned elbow_rotations_
Definition: pose.hpp:128
void setRobotPose(const Eigen::Isometry3d &pose)
Definition: pose.cpp:381
MovementType move_type_
Definition: pose.hpp:120
SpeedType
Definition: pose.hpp:26
NonFlip.
std::tuple< FlipNonFlip, Elbow, BackFront > Config
Definition: pose.hpp:61
bool is_pose_id_
Definition: pose.hpp:118
std::string getPoseLinesString() const
Definition: pose.cpp:270
Flip.
unsigned flipnonflip_rotations_
Definition: pose.hpp:128
Definition: pose.hpp:20
bool hasSameGroupsAxes(const FanucPose &other) const
Definition: pose.cpp:91
Definition: pose.hpp:28
SpeedType speed_type_
Definition: pose.hpp:122
unsigned backfront_rotations_
Definition: pose.hpp:128


fanuc_post_processor
Author(s): Victor Lamoine - Institut Maupertuis
autogenerated on Mon Jun 10 2019 13:16:56