#include <pose.hpp>
|
| enum | BackFront { BackFront::Back,
BackFront::Front
} |
| |
| using | Config = std::tuple< FlipNonFlip, Elbow, BackFront > |
| |
| enum | Elbow { Elbow::Up,
Elbow::Down
} |
| |
| enum | FlipNonFlip { FlipNonFlip::Flip,
FlipNonFlip::NonFlip
} |
| |
| enum | MovementType { JOINT,
LINEAR
} |
| |
| enum | SpeedType {
MM_SEC,
CM_SEC,
M_SEC,
MM_MIN,
CM_MIN,
M_MIN,
DEG_SEC,
PERCENTAGE
} |
| |
Definition at line 13 of file pose.hpp.
◆ Config
◆ BackFront
◆ Elbow
◆ FlipNonFlip
Robot configuration
| Enumerator |
|---|
| Flip | Flip.
|
| NonFlip | NonFlip.
|
Definition at line 37 of file pose.hpp.
◆ MovementType
Fanuc movement types Other types are not supported (circular etc.)
Definition at line 20 of file pose.hpp.
◆ SpeedType
Fanuc speed types Other types are not supported (SEC, MSEC, MAX_SPEED)
| Enumerator |
|---|
| MM_SEC | |
| CM_SEC | |
| M_SEC | |
| MM_MIN | |
| CM_MIN | |
| M_MIN | |
| DEG_SEC | |
| PERCENTAGE | |
Definition at line 29 of file pose.hpp.
◆ FanucPose()
| fanuc_post_processor::FanucPose::FanucPose |
( |
const std::vector< FanucAxis > |
extended_axes = {}, |
|
|
const std::vector< FanucGroup > |
extra_groups = {} |
|
) |
| |
Construct a Fanuc pose
- Parameters
-
| extended_axes | 1 or more axis added to group 1 |
| extra_groups | group 2, 3 etc. |
Definition at line 6 of file pose.cpp.
◆ ~FanucPose()
| fanuc_post_processor::FanucPose::~FanucPose |
( |
| ) |
|
|
virtual |
◆ configurationToString()
| std::string fanuc_post_processor::FanucPose::configurationToString |
( |
| ) |
const |
|
private |
◆ getMainLineString()
| std::string fanuc_post_processor::FanucPose::getMainLineString |
( |
| ) |
const |
- Returns
- a string containing the /MN program line corresponding to this pose
Definition at line 244 of file pose.cpp.
◆ getPoseLinesString()
| std::string fanuc_post_processor::FanucPose::getPoseLinesString |
( |
| ) |
const |
- Returns
- a string containing the /POS program lines corresponding to this pose
Definition at line 279 of file pose.cpp.
◆ hasSameGroupsAxes()
| bool fanuc_post_processor::FanucPose::hasSameGroupsAxes |
( |
const FanucPose & |
other | ) |
const |
Checks if poses have the same groups/axes per groups Does NOT check that user frame, user tool, pose are identical!
- Parameters
-
- Returns
- true if poses have the same groups/axes per groups
Definition at line 93 of file pose.cpp.
◆ isValid()
| bool fanuc_post_processor::FanucPose::isValid |
( |
| ) |
const |
Check if all units/fields are valid
- Returns
- true if valid, false otherwise
Definition at line 115 of file pose.cpp.
◆ movementTypeToString()
| std::string fanuc_post_processor::FanucPose::movementTypeToString |
( |
| ) |
const |
|
private |
◆ setRobotPose()
| void fanuc_post_processor::FanucPose::setRobotPose |
( |
const Eigen::Isometry3d & |
pose | ) |
|
Modifies the first 6 axes values of the group 1 to the specified pose
- Parameters
-
Definition at line 390 of file pose.cpp.
◆ speedTypeToString()
| std::string fanuc_post_processor::FanucPose::speedTypeToString |
( |
| ) |
const |
|
private |
◆ acc_
| unsigned fanuc_post_processor::FanucPose::acc_ = 100 |
◆ backfront_rotations_
| int fanuc_post_processor::FanucPose::backfront_rotations_ = 0 |
◆ cnt_
| unsigned fanuc_post_processor::FanucPose::cnt_ = 100 |
◆ configuration_
| Config fanuc_post_processor::FanucPose::configuration_ |
◆ elbow_rotations_
| int fanuc_post_processor::FanucPose::elbow_rotations_ = 0 |
◆ flipnonflip_rotations_
| int fanuc_post_processor::FanucPose::flipnonflip_rotations_ = 0 |
◆ groups_
| std::vector<FanucGroup> fanuc_post_processor::FanucPose::groups_ |
◆ is_pose_id_
| bool fanuc_post_processor::FanucPose::is_pose_id_ = false |
◆ move_type_
| MovementType fanuc_post_processor::FanucPose::move_type_ = MovementType::LINEAR |
◆ option_
| std::string fanuc_post_processor::FanucPose::option_ |
◆ pose_id_
| unsigned fanuc_post_processor::FanucPose::pose_id_ = 1 |
◆ speed_
| double fanuc_post_processor::FanucPose::speed_ = 10 |
◆ speed_register_
| bool fanuc_post_processor::FanucPose::speed_register_ = false |
◆ speed_type_
| SpeedType fanuc_post_processor::FanucPose::speed_type_ = SpeedType::CM_MIN |
The documentation for this class was generated from the following files: