Public Types | Public Member Functions | Public Attributes | Private Member Functions | List of all members
fanuc_post_processor::FanucPose Class Reference

#include <pose.hpp>

Public Types

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
}
 

Public Member Functions

 FanucPose (const std::vector< FanucAxis > extended_axes={}, const std::vector< FanucGroup > extra_groups={})
 
std::string getMainLineString () const
 
std::string getPoseLinesString () const
 
bool hasSameGroupsAxes (const FanucPose &other) const
 
bool isValid () const
 
void setRobotPose (const Eigen::Isometry3d &pose)
 
virtual ~FanucPose ()
 

Public Attributes

unsigned acc_ = 100
 
int backfront_rotations_ = 0
 
unsigned cnt_ = 100
 
Config configuration_
 
int elbow_rotations_ = 0
 
int flipnonflip_rotations_ = 0
 
std::vector< FanucGroupgroups_
 
bool is_pose_id_ = false
 
MovementType move_type_ = MovementType::LINEAR
 
std::string option_
 
unsigned pose_id_ = 1
 
double speed_ = 10
 
bool speed_register_ = false
 
SpeedType speed_type_ = SpeedType::CM_MIN
 

Private Member Functions

std::string configurationToString () const
 
std::string movementTypeToString () const
 
std::string speedTypeToString () const
 

Detailed Description

Definition at line 13 of file pose.hpp.

Member Typedef Documentation

◆ Config

Robot configuration

Definition at line 64 of file pose.hpp.

Member Enumeration Documentation

◆ BackFront

Robot configuration

Enumerator
Back 
Front 

Definition at line 55 of file pose.hpp.

◆ Elbow

Robot configuration

Enumerator
Up 
Down 

Definition at line 46 of file pose.hpp.

◆ 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.)

Enumerator
JOINT 
LINEAR 

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.

Constructor & Destructor Documentation

◆ FanucPose()

fanuc_post_processor::FanucPose::FanucPose ( const std::vector< FanucAxis extended_axes = {},
const std::vector< FanucGroup extra_groups = {} 
)

Construct a Fanuc pose

Parameters
extended_axes1 or more axis added to group 1
extra_groupsgroup 2, 3 etc.

Definition at line 6 of file pose.cpp.

◆ ~FanucPose()

fanuc_post_processor::FanucPose::~FanucPose ( )
virtual

Definition at line 35 of file pose.cpp.

Member Function Documentation

◆ configurationToString()

std::string fanuc_post_processor::FanucPose::configurationToString ( ) const
private

Definition at line 71 of file pose.cpp.

◆ 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
other
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

Definition at line 39 of file pose.cpp.

◆ 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
posespecified pose

Definition at line 390 of file pose.cpp.

◆ speedTypeToString()

std::string fanuc_post_processor::FanucPose::speedTypeToString ( ) const
private

Definition at line 49 of file pose.cpp.

Member Data Documentation

◆ acc_

unsigned fanuc_post_processor::FanucPose::acc_ = 100

Definition at line 129 of file pose.hpp.

◆ backfront_rotations_

int fanuc_post_processor::FanucPose::backfront_rotations_ = 0

Definition at line 132 of file pose.hpp.

◆ cnt_

unsigned fanuc_post_processor::FanucPose::cnt_ = 100

Definition at line 128 of file pose.hpp.

◆ configuration_

Config fanuc_post_processor::FanucPose::configuration_

Definition at line 131 of file pose.hpp.

◆ elbow_rotations_

int fanuc_post_processor::FanucPose::elbow_rotations_ = 0

Definition at line 132 of file pose.hpp.

◆ flipnonflip_rotations_

int fanuc_post_processor::FanucPose::flipnonflip_rotations_ = 0

Definition at line 132 of file pose.hpp.

◆ groups_

std::vector<FanucGroup> fanuc_post_processor::FanucPose::groups_

Definition at line 133 of file pose.hpp.

◆ is_pose_id_

bool fanuc_post_processor::FanucPose::is_pose_id_ = false

Definition at line 121 of file pose.hpp.

◆ move_type_

MovementType fanuc_post_processor::FanucPose::move_type_ = MovementType::LINEAR

Definition at line 123 of file pose.hpp.

◆ option_

std::string fanuc_post_processor::FanucPose::option_

Definition at line 134 of file pose.hpp.

◆ pose_id_

unsigned fanuc_post_processor::FanucPose::pose_id_ = 1

Definition at line 122 of file pose.hpp.

◆ speed_

double fanuc_post_processor::FanucPose::speed_ = 10

Definition at line 124 of file pose.hpp.

◆ speed_register_

bool fanuc_post_processor::FanucPose::speed_register_ = false

Definition at line 130 of file pose.hpp.

◆ speed_type_

SpeedType fanuc_post_processor::FanucPose::speed_type_ = SpeedType::CM_MIN

Definition at line 125 of file pose.hpp.


The documentation for this class was generated from the following files:


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