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 <industrial_robot_angle_conversions/poses.hpp>
7 #include <ros/ros.h>
8 #include <tuple>
9 
10 namespace fanuc_post_processor
11 {
12 
13 class FanucPose
14 {
15 public:
21  {
23  };
24 
29  enum SpeedType
30  {
32  };
33 
37  enum class FlipNonFlip
38  {
39  Flip,
40  NonFlip
41  };
42 
46  enum class Elbow
47  {
48  Up,
49  Down
50  };
51 
55  enum class BackFront
56  {
57  Back,
58  Front
59  };
60 
64  using Config = std::tuple<FlipNonFlip, Elbow, BackFront>;
65 
66 private:
67  std::string
68  movementTypeToString() const;
69 
70  std::string
71  speedTypeToString() const;
72 
73  std::string
74  configurationToString() const;
75 
76 public:
77 
83  FanucPose(const std::vector<FanucAxis> extended_axes = {},
84  const std::vector<FanucGroup> extra_groups = {});
85 
86  virtual ~FanucPose();
87 
95  bool hasSameGroupsAxes(const FanucPose &other) const;
96 
101  bool isValid() const;
102 
106  std::string getMainLineString() const;
107 
111  std::string getPoseLinesString() const;
112 
117  void setRobotPose(const Eigen::Isometry3d &pose);
118 
119  // If true: this pose is only a duplicate of an existing pose in the program
120  // The existence will be verified when adding the pose
121  bool is_pose_id_ = false;
122  unsigned pose_id_ = 1; // Unique within a Fanuc program. Cannot be zero
123  MovementType move_type_ = MovementType::LINEAR;
124  double speed_ = 10;
125  SpeedType speed_type_ = SpeedType::CM_MIN;
126  // CNT = 0 == Fine
127  // CNT 1-100 is smooth motion
128  unsigned cnt_ = 100;
129  unsigned acc_ = 100;
130  bool speed_register_ = false; // If true, speed will be converted to unsigned and used as a register number
133  std::vector<FanucGroup> groups_;
134  std::string option_; // Time before, time after, offset PR etc...
135 };
136 
137 }
138 
139 #endif
Definition: axis.hpp:6
bool speed_register_
Definition: pose.hpp:130
std::string configurationToString() const
Definition: pose.cpp:71
int elbow_rotations_
Definition: pose.hpp:132
FlipNonFlip
Definition: pose.hpp:37
unsigned cnt_
Definition: pose.hpp:128
FanucPose(const std::vector< FanucAxis > extended_axes={}, const std::vector< FanucGroup > extra_groups={})
Definition: pose.cpp:6
MovementType
Definition: pose.hpp:20
Definition: pose.hpp:31
std::string movementTypeToString() const
Definition: pose.cpp:39
Definition: pose.hpp:31
Definition: pose.hpp:13
std::tuple< FlipNonFlip, Elbow, BackFront > Config
Definition: pose.hpp:64
BackFront
Definition: pose.hpp:55
Definition: pose.hpp:31
virtual ~FanucPose()
Definition: pose.cpp:35
Config configuration_
Definition: pose.hpp:131
Definition: pose.hpp:31
Definition: pose.hpp:31
Elbow
Definition: pose.hpp:46
Definition: pose.hpp:31
unsigned pose_id_
Definition: pose.hpp:122
std::vector< FanucGroup > groups_
Definition: pose.hpp:133
Definition: pose.hpp:31
unsigned acc_
Definition: pose.hpp:129
std::string getMainLineString() const
Definition: pose.cpp:244
double speed_
Definition: pose.hpp:124
int backfront_rotations_
Definition: pose.hpp:132
Definition: pose.hpp:22
std::string option_
Definition: pose.hpp:134
void setRobotPose(const Eigen::Isometry3d &pose)
Definition: pose.cpp:390
MovementType move_type_
Definition: pose.hpp:123
int flipnonflip_rotations_
Definition: pose.hpp:132
SpeedType
Definition: pose.hpp:29
bool hasSameGroupsAxes(const FanucPose &other) const
Definition: pose.cpp:93
NonFlip.
bool is_pose_id_
Definition: pose.hpp:121
Flip.
Definition: pose.hpp:22
std::string speedTypeToString() const
Definition: pose.cpp:49
std::string getPoseLinesString() const
Definition: pose.cpp:279
bool isValid() const
Definition: pose.cpp:115
Definition: pose.hpp:31
SpeedType speed_type_
Definition: pose.hpp:125


fanuc_post_processor
Author(s): Victor Lamoine - Institut Maupertuis
autogenerated on Mon Feb 28 2022 22:20:38