#include <pose.hpp>
|
enum | BackFront { BackFront::Back,
BackFront::Front
} |
|
typedef std::tuple< FlipNonFlip, Elbow, BackFront > | Config |
|
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,
PERCENTAGE
} |
|
Definition at line 12 of file pose.hpp.
Robot configuration
Definition at line 61 of file pose.hpp.
Robot configuration
Definition at line 52 of file pose.hpp.
Robot configuration
Definition at line 43 of file pose.hpp.
Robot configuration
Enumerator |
---|
Flip |
Flip.
|
NonFlip |
NonFlip.
|
Definition at line 34 of file pose.hpp.
Fanuc movement types
Definition at line 18 of file pose.hpp.
Fanuc speed types
Enumerator |
---|
MM_SEC |
|
CM_SEC |
|
M_SEC |
|
MM_MIN |
|
CM_MIN |
|
M_MIN |
|
PERCENTAGE |
|
Definition at line 26 of file pose.hpp.
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.
fanuc_post_processor::FanucPose::~FanucPose |
( |
| ) |
|
|
virtual |
std::string fanuc_post_processor::FanucPose::configurationToString |
( |
| ) |
const |
|
private |
std::string fanuc_post_processor::FanucPose::getMainLineString |
( |
| ) |
const |
- Returns
- a string containing the /MN program line corresponding to this pose
Definition at line 242 of file pose.cpp.
std::string fanuc_post_processor::FanucPose::getPoseLinesString |
( |
| ) |
const |
- Returns
- a string containing the /POS program lines corresponding to this pose
Definition at line 270 of file pose.cpp.
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 91 of file pose.cpp.
bool fanuc_post_processor::FanucPose::isValid |
( |
| ) |
const |
Check if all units/fields are valid
- Returns
- true if valid, false otherwise
Definition at line 113 of file pose.cpp.
std::string fanuc_post_processor::FanucPose::movementTypeToString |
( |
| ) |
const |
|
private |
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 381 of file pose.cpp.
std::string fanuc_post_processor::FanucPose::speedTypeToString |
( |
| ) |
const |
|
private |
unsigned fanuc_post_processor::FanucPose::backfront_rotations_ = 0 |
unsigned fanuc_post_processor::FanucPose::cnt_ = 100 |
Config fanuc_post_processor::FanucPose::configuration_ |
unsigned fanuc_post_processor::FanucPose::elbow_rotations_ = 0 |
unsigned fanuc_post_processor::FanucPose::flipnonflip_rotations_ = 0 |
std::vector<FanucGroup> fanuc_post_processor::FanucPose::groups_ |
bool fanuc_post_processor::FanucPose::is_pose_id_ = false |
MovementType fanuc_post_processor::FanucPose::move_type_ = MovementType::LINEAR |
std::string fanuc_post_processor::FanucPose::option_ |
unsigned fanuc_post_processor::FanucPose::pose_id_ = 1 |
double fanuc_post_processor::FanucPose::speed_ = 10 |
bool fanuc_post_processor::FanucPose::speed_register_ = false |
SpeedType fanuc_post_processor::FanucPose::speed_type_ = SpeedType::CM_MIN |
The documentation for this class was generated from the following files: