Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes
mtconnect_state_machine::StateMachine Class Reference

#include <state_machine.h>

List of all members.

Public Member Functions

bool init ()
 Initializes statemachine, ros node, servers, and clients.
void run ()
 Execute state machine (blocks permanently)
void runOnce ()
 Execute state machine once.
 StateMachine ()
 Default constructor (must call init function)
 ~StateMachine ()
 Deconstructor.

Protected Member Functions

void abortActionServers ()
 Aborts any server with active client requests.
bool areActionsReady ()
 Checks remote action servers to see if they are ready.
bool areServicesReady ()
 Checks remote services to see if they are ready.
void callPublishers ()
void cancelActionClients ()
 Cancels any requests to action servers.
void closeChuck ()
void closeDoor ()
void closeGripper ()
void errorChecks ()
bool externalCommandCB (mtconnect_example_msgs::StateMachineCmd::Request &req, mtconnect_example_msgs::StateMachineCmd::Response &res)
StateType getState ()
bool isActionComplete (int action_state)
bool isChuckClosed ()
bool isChuckOpened ()
bool isDoorClosed ()
bool isDoorOpened ()
bool isGripperClosed ()
bool isGripperOpened ()
bool isHome ()
bool isMoveDone ()
void jointStatesCB (const sensor_msgs::JointStateConstPtr &msg)
void materialLoadGoalCB ()
void materialUnloadGoalCB ()
bool moveArm (const std::string &move_name)
void openChuck ()
void openDoor ()
void openGripper ()
void overrideChecks ()
void robotSpindlePublisher ()
void robotStatusCB (const industrial_msgs::RobotStatusConstPtr &msg)
void robotStatusPublisher ()
bool setMatActionsNotReady ()
 Checks remote services to see if they are ready.
bool setMatActionsReady ()
 Checks remote services to see if they are ready.
bool setMatLoad (int state)
 Checks remote services to see if they are ready.
bool setMatUnload (int state)
void setState (StateType state)
void stateMachineStatusPublisher ()

Protected Attributes

ros::NodeHandle nh_
 Internal node handle.

Private Attributes

CncCloseChuckClientPtr close_chuck_client_ptr_
CncCloseDoorClientPtr close_door_client_ptr_
bool cycle_stop_req_
 cycle stop request flat
ros::ServiceServer external_command_srv_
GraspActionClientPtr grasp_action_client_ptr_
boost::shared_ptr
< mtconnect::JointPoint
home_
bool home_check_
 enables/disables home checking
double home_tol_
 home position tolerance
std::map< std::string,
trajectory_msgs::JointTrajectoryPtr > 
joint_paths_
sensor_msgs::JointState joint_state_msg_
ros::Subscriber joint_states_sub_
JointTractoryClientPtr joint_traj_client_ptr_
control_msgs::FollowJointTrajectoryGoal joint_traj_goal_
int loop_rate_
 Main loop rate.
mtconnect_msgs::SetMTConnectState mat_load_set_state_
mtconnect_msgs::SetMTConnectState mat_unload_set_state_
MaterialLoadServerPtr material_load_server_ptr_
ros::ServiceClient material_load_set_state_client_
int material_load_state_
 internal flag to track material load state (should be encapsulated in material load)
bool material_state_
 material state (true if material is present)
MaterialUnloadServerPtr material_unload_server_ptr_
ros::ServiceClient material_unload_set_state_client_
CncOpenChuckClientPtr open_chuck_client_ptr_
CncOpenDoorClientPtr open_door_client_ptr_
mtconnect_msgs::RobotSpindle robot_spindle_msg_
ros::Publisher robot_spindle_pub_
mtconnect_msgs::RobotStates robot_state_msg_
ros::Publisher robot_states_pub_
industrial_msgs::RobotStatus robot_status_msg_
ros::Subscriber robot_status_sub_
StateType state_
 Holds current state.
ros::Publisher state_machine_pub_
mtconnect_example_msgs::StateMachineStatus state_machine_stat_msg_
arm_navigation_msgs::FilterJointTrajectoryWithConstraints trajectory_filter_
ros::ServiceClient trajectory_filter_client_
GraspActionClientPtr vise_action_client_ptr_

Detailed Description

Definition at line 182 of file state_machine.h.


Constructor & Destructor Documentation

Default constructor (must call init function)

Definition at line 69 of file state_machine.cpp.

Deconstructor.

Definition at line 82 of file state_machine.cpp.


Member Function Documentation

void StateMachine::abortActionServers ( ) [protected]

Aborts any server with active client requests.

Definition at line 586 of file state_machine.cpp.

Checks remote action servers to see if they are ready.

Returns:
true if all ready, otherwise false

Definition at line 572 of file state_machine.cpp.

Checks remote services to see if they are ready.

Returns:
true if all ready, otherwise false

Definition at line 580 of file state_machine.cpp.

void StateMachine::callPublishers ( ) [protected]

Definition at line 745 of file state_machine.cpp.

void StateMachine::cancelActionClients ( ) [protected]

Cancels any requests to action servers.

Definition at line 607 of file state_machine.cpp.

void StateMachine::closeChuck ( ) [protected]

Definition at line 1033 of file state_machine.cpp.

void StateMachine::closeDoor ( ) [protected]

Definition at line 1001 of file state_machine.cpp.

void StateMachine::closeGripper ( ) [protected]

Definition at line 1066 of file state_machine.cpp.

void StateMachine::errorChecks ( ) [protected]

Definition at line 688 of file state_machine.cpp.

Definition at line 853 of file state_machine.cpp.

Definition at line 233 of file state_machine.h.

Initializes statemachine, ros node, servers, and clients.

Returns:
true on success, false otherwise.

Definition at line 87 of file state_machine.cpp.

bool StateMachine::isActionComplete ( int  action_state) [protected]

Definition at line 909 of file state_machine.cpp.

Definition at line 1047 of file state_machine.cpp.

Definition at line 1028 of file state_machine.cpp.

Definition at line 1009 of file state_machine.cpp.

Definition at line 996 of file state_machine.cpp.

Definition at line 1074 of file state_machine.cpp.

Definition at line 1061 of file state_machine.cpp.

bool StateMachine::isHome ( ) [protected]

Definition at line 1079 of file state_machine.cpp.

bool StateMachine::isMoveDone ( ) [protected]

Definition at line 983 of file state_machine.cpp.

Definition at line 848 of file state_machine.cpp.

void StateMachine::materialLoadGoalCB ( ) [protected]

Definition at line 805 of file state_machine.cpp.

void StateMachine::materialUnloadGoalCB ( ) [protected]

Definition at line 824 of file state_machine.cpp.

bool StateMachine::moveArm ( const std::string &  move_name) [protected]

Definition at line 944 of file state_machine.cpp.

void StateMachine::openChuck ( ) [protected]

Definition at line 1014 of file state_machine.cpp.

void StateMachine::openDoor ( ) [protected]

Definition at line 988 of file state_machine.cpp.

void StateMachine::openGripper ( ) [protected]

Definition at line 1053 of file state_machine.cpp.

void StateMachine::overrideChecks ( ) [protected]

Definition at line 711 of file state_machine.cpp.

Definition at line 781 of file state_machine.cpp.

void StateMachine::robotStatusCB ( const industrial_msgs::RobotStatusConstPtr &  msg) [protected]

Definition at line 843 of file state_machine.cpp.

void StateMachine::robotStatusPublisher ( ) [protected]

Definition at line 751 of file state_machine.cpp.

void StateMachine::run ( void  )

Execute state machine (blocks permanently)

Executes the state machine. Handles all transitions

Definition at line 182 of file state_machine.cpp.

Execute state machine once.

Definition at line 200 of file state_machine.cpp.

Checks remote services to see if they are ready.

Returns:
true if all ready, otherwise false

Definition at line 627 of file state_machine.cpp.

Checks remote services to see if they are ready.

Returns:
true if all ready, otherwise false

Definition at line 621 of file state_machine.cpp.

bool StateMachine::setMatLoad ( int  state) [protected]

Checks remote services to see if they are ready.

Returns:
true if all ready, otherwise false

Definition at line 633 of file state_machine.cpp.

bool StateMachine::setMatUnload ( int  state) [protected]

Definition at line 661 of file state_machine.cpp.

void mtconnect_state_machine::StateMachine::setState ( StateType  state) [inline, protected]

Definition at line 225 of file state_machine.h.

Definition at line 794 of file state_machine.cpp.


Member Data Documentation

Definition at line 399 of file state_machine.h.

Definition at line 397 of file state_machine.h.

cycle stop request flat

Definition at line 373 of file state_machine.h.

Definition at line 414 of file state_machine.h.

Definition at line 400 of file state_machine.h.

Definition at line 389 of file state_machine.h.

enables/disables home checking

Definition at line 362 of file state_machine.h.

home position tolerance

Definition at line 368 of file state_machine.h.

std::map<std::string, trajectory_msgs::JointTrajectoryPtr> mtconnect_state_machine::StateMachine::joint_paths_ [private]

Definition at line 388 of file state_machine.h.

Definition at line 427 of file state_machine.h.

Definition at line 411 of file state_machine.h.

Definition at line 402 of file state_machine.h.

Definition at line 437 of file state_machine.h.

Main loop rate.

Definition at line 356 of file state_machine.h.

mtconnect_msgs::SetMTConnectState mtconnect_state_machine::StateMachine::mat_load_set_state_ [private]

Definition at line 432 of file state_machine.h.

mtconnect_msgs::SetMTConnectState mtconnect_state_machine::StateMachine::mat_unload_set_state_ [private]

Definition at line 433 of file state_machine.h.

Definition at line 392 of file state_machine.h.

Definition at line 417 of file state_machine.h.

internal flag to track material load state (should be encapsulated in material load)

Definition at line 385 of file state_machine.h.

material state (true if material is present)

Definition at line 379 of file state_machine.h.

Definition at line 393 of file state_machine.h.

Definition at line 418 of file state_machine.h.

Internal node handle.

Definition at line 237 of file state_machine.h.

Definition at line 398 of file state_machine.h.

Definition at line 396 of file state_machine.h.

mtconnect_msgs::RobotSpindle mtconnect_state_machine::StateMachine::robot_spindle_msg_ [private]

Definition at line 423 of file state_machine.h.

Definition at line 406 of file state_machine.h.

mtconnect_msgs::RobotStates mtconnect_state_machine::StateMachine::robot_state_msg_ [private]

Definition at line 422 of file state_machine.h.

Definition at line 405 of file state_machine.h.

industrial_msgs::RobotStatus mtconnect_state_machine::StateMachine::robot_status_msg_ [private]

Definition at line 428 of file state_machine.h.

Definition at line 410 of file state_machine.h.

Holds current state.

Definition at line 350 of file state_machine.h.

Definition at line 407 of file state_machine.h.

Definition at line 424 of file state_machine.h.

Definition at line 434 of file state_machine.h.

Definition at line 419 of file state_machine.h.

Definition at line 401 of file state_machine.h.


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


mtconnect_state_machine
Author(s): Shaun M. Edwards
autogenerated on Mon Jan 6 2014 11:30:58