Classes | Namespaces | Typedefs | Enumerations | Variables
state_machine.h File Reference
#include <boost/thread/mutex.hpp>
#include <boost/thread/thread.hpp>
#include <boost/assign/list_of.hpp>
#include <boost/assign/list_inserter.hpp>
#include <ros/ros.h>
#include <arm_navigation_msgs/GetPlanningScene.h>
#include <arm_navigation_msgs/SetPlanningSceneDiff.h>
#include <planning_environment/models/collision_models.h>
#include <planning_environment/models/model_utils.h>
#include <actionlib/client/simple_action_client.h>
#include <arm_navigation_msgs/MoveArmAction.h>
#include <arm_navigation_msgs/SimplePoseConstraint.h>
#include <arm_navigation_msgs/FilterJointTrajectoryWithConstraints.h>
#include <nav_msgs/Path.h>
#include <tf/tf.h>
#include <tf/transform_listener.h>
#include <geometry_msgs/PoseArray.h>
#include <boost/tuple/tuple.hpp>
#include <mtconnect_cnc_robot_example/utilities/utilities.h>
#include <mtconnect_cnc_robot_example/move_arm_action_clients/MoveArmActionClient.h>
#include <mtconnect_cnc_robot_example/Command.h>
#include <boost/enable_shared_from_this.hpp>
#include <industrial_msgs/RobotStatus.h>
#include <mtconnect_msgs/CloseChuckAction.h>
#include <mtconnect_msgs/OpenChuckAction.h>
#include <mtconnect_msgs/CloseDoorAction.h>
#include <mtconnect_msgs/OpenDoorAction.h>
#include <mtconnect_msgs/MaterialLoadAction.h>
#include <mtconnect_msgs/MaterialUnloadAction.h>
#include <object_manipulation_msgs/PickupAction.h>
#include <object_manipulation_msgs/PlaceAction.h>
#include <mtconnect_cnc_robot_example/state_machine/state_machine_interface.h>
#include <object_manipulation_msgs/GraspHandPostureExecutionAction.h>
#include <actionlib/server/simple_action_server.h>
#include <mtconnect_msgs/RobotSpindle.h>
#include <mtconnect_msgs/RobotStates.h>
#include <mtconnect_msgs/SetMTConnectState.h>
#include <control_msgs/FollowJointTrajectoryAction.h>
Include dependency graph for state_machine.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  mtconnect_cnc_robot_example::state_machine::StateMachine

Namespaces

namespace  mtconnect_cnc_robot_example
namespace  mtconnect_cnc_robot_example::state_machine
namespace  mtconnect_cnc_robot_example::state_machine::tasks

Typedefs

typedef
actionlib::SimpleActionClient
< mtconnect_msgs::CloseChuckAction > 
CncCloseChuckClient
typedef boost::shared_ptr
< CncCloseChuckClient
CncCloseChuckClientPtr
typedef
actionlib::SimpleActionClient
< mtconnect_msgs::CloseDoorAction > 
CncCloseDoorClient
typedef boost::shared_ptr
< CncCloseDoorClient
CncCloseDoorClientPtr
typedef
actionlib::SimpleActionClient
< mtconnect_msgs::OpenChuckAction > 
CncOpenChuckClient
typedef boost::shared_ptr
< CncOpenChuckClient
CncOpenChuckClientPtr
typedef
actionlib::SimpleActionClient
< mtconnect_msgs::OpenDoorAction > 
CncOpenDoorClient
typedef boost::shared_ptr
< CncOpenDoorClient
CncOpenDoorClientPtr
typedef
actionlib::SimpleActionClient
< object_manipulation_msgs::GraspHandPostureExecutionAction > 
GraspActionClient
typedef boost::shared_ptr
< GraspActionClient
GraspActionClientPtr
typedef
actionlib::SimpleActionClient
< control_msgs::FollowJointTrajectoryAction
JointTractoryClient
typedef boost::shared_ptr
< JointTractoryClient
JointTractoryClientPtr
typedef std::vector< int > MaterialHandlingSequence
typedef
actionlib::SimpleActionServer
< mtconnect_msgs::MaterialLoadAction > 
MaterialLoadServer
typedef boost::shared_ptr
< MaterialLoadServer
MaterialLoadServerPtr
typedef
actionlib::SimpleActionServer
< mtconnect_msgs::MaterialUnloadAction > 
MaterialUnloadServer
typedef boost::shared_ptr
< MaterialUnloadServer
MaterialUnloadServerPtr
typedef
actionlib::SimpleActionClient
< arm_navigation_msgs::MoveArmAction
MoveArmClient
typedef boost::shared_ptr
< MoveArmClient
MoveArmClientPtr
typedef
actionlib::SimpleActionClient
< object_manipulation_msgs::PickupAction > 
MovePickupClient
typedef boost::shared_ptr
< MovePickupClient
MovePickupClientPtr
typedef
actionlib::SimpleActionClient
< object_manipulation_msgs::PlaceAction > 
MovePlaceClient
typedef boost::shared_ptr
< MovePlaceClient
MovePlaceClientPtr

Enumerations

enum  mtconnect_cnc_robot_example::state_machine::tasks::Task {
  mtconnect_cnc_robot_example::state_machine::tasks::NO_TASK = int(0), mtconnect_cnc_robot_example::state_machine::tasks::ROBOT_PLACE_WORKPIECE, mtconnect_cnc_robot_example::state_machine::tasks::ROBOT_PICKUP_MATERIAL, mtconnect_cnc_robot_example::state_machine::tasks::ROBOT_APPROACH_CNC,
  mtconnect_cnc_robot_example::state_machine::tasks::ROBOT_ENTER_CNC, mtconnect_cnc_robot_example::state_machine::tasks::ROBOT_MOVE_TO_CHUCK, mtconnect_cnc_robot_example::state_machine::tasks::ROBOT_RETREAT_FROM_CHUCK, mtconnect_cnc_robot_example::state_machine::tasks::ROBOT_EXIT_CNC,
  mtconnect_cnc_robot_example::state_machine::tasks::ROBOT_MOVE_HOME, mtconnect_cnc_robot_example::state_machine::tasks::ROBOT_MOVE_WAIT, mtconnect_cnc_robot_example::state_machine::tasks::ROBOT_CARTESIAN_MOVE, mtconnect_cnc_robot_example::state_machine::tasks::CNC_OPEN_DOOR,
  mtconnect_cnc_robot_example::state_machine::tasks::CNC_CLOSE_DOOR, mtconnect_cnc_robot_example::state_machine::tasks::CNC_OPEN_CHUCK, mtconnect_cnc_robot_example::state_machine::tasks::CNC_CLOSE_CHUCK, mtconnect_cnc_robot_example::state_machine::tasks::VISE_OPEN,
  mtconnect_cnc_robot_example::state_machine::tasks::VISE_CLOSE, mtconnect_cnc_robot_example::state_machine::tasks::GRIPPER_OPEN, mtconnect_cnc_robot_example::state_machine::tasks::GRIPPER_CLOSE, mtconnect_cnc_robot_example::state_machine::tasks::MATERIAL_LOAD_START,
  mtconnect_cnc_robot_example::state_machine::tasks::MATERIAL_LOAD_END, mtconnect_cnc_robot_example::state_machine::tasks::MATERIAL_UNLOAD_START, mtconnect_cnc_robot_example::state_machine::tasks::MATERIAL_UNLOAD_END, mtconnect_cnc_robot_example::state_machine::tasks::TEST_TASK_START,
  mtconnect_cnc_robot_example::state_machine::tasks::TEST_TASK_END, mtconnect_cnc_robot_example::state_machine::tasks::JM_HOME_TO_READY, mtconnect_cnc_robot_example::state_machine::tasks::JM_READY_TO_APPROACH, mtconnect_cnc_robot_example::state_machine::tasks::JM_APPROACH_TO_PICK,
  mtconnect_cnc_robot_example::state_machine::tasks::JM_PICK_TO_DOOR, mtconnect_cnc_robot_example::state_machine::tasks::JM_DOOR_TO_CHUCK, mtconnect_cnc_robot_example::state_machine::tasks::JM_CHUCK_TO_READY, mtconnect_cnc_robot_example::state_machine::tasks::JM_READY_TO_DOOR,
  mtconnect_cnc_robot_example::state_machine::tasks::JM_PICK_TO_HOME
}

Variables

static std::map< int, std::string > mtconnect_cnc_robot_example::state_machine::tasks::TASK_MAP

Typedef Documentation

typedef actionlib::SimpleActionClient<mtconnect_msgs::CloseChuckAction> CncCloseChuckClient

Definition at line 68 of file state_machine.h.

typedef boost::shared_ptr<CncCloseChuckClient> CncCloseChuckClientPtr

Definition at line 79 of file state_machine.h.

typedef actionlib::SimpleActionClient<mtconnect_msgs::CloseDoorAction> CncCloseDoorClient

Definition at line 66 of file state_machine.h.

typedef boost::shared_ptr<CncCloseDoorClient> CncCloseDoorClientPtr

Definition at line 77 of file state_machine.h.

typedef actionlib::SimpleActionClient<mtconnect_msgs::OpenChuckAction> CncOpenChuckClient

Definition at line 67 of file state_machine.h.

typedef boost::shared_ptr<CncOpenChuckClient> CncOpenChuckClientPtr

Definition at line 78 of file state_machine.h.

typedef actionlib::SimpleActionClient<mtconnect_msgs::OpenDoorAction> CncOpenDoorClient

Definition at line 65 of file state_machine.h.

typedef boost::shared_ptr<CncOpenDoorClient> CncOpenDoorClientPtr

Definition at line 76 of file state_machine.h.

typedef actionlib::SimpleActionClient<object_manipulation_msgs::GraspHandPostureExecutionAction> GraspActionClient

Definition at line 71 of file state_machine.h.

typedef boost::shared_ptr<GraspActionClient> GraspActionClientPtr

Definition at line 82 of file state_machine.h.

Definition at line 72 of file state_machine.h.

typedef boost::shared_ptr<JointTractoryClient> JointTractoryClientPtr

Definition at line 83 of file state_machine.h.

Definition at line 84 of file state_machine.h.

typedef actionlib::SimpleActionServer<mtconnect_msgs::MaterialLoadAction> MaterialLoadServer

Definition at line 69 of file state_machine.h.

typedef boost::shared_ptr<MaterialLoadServer> MaterialLoadServerPtr

Definition at line 80 of file state_machine.h.

typedef actionlib::SimpleActionServer<mtconnect_msgs::MaterialUnloadAction> MaterialUnloadServer

Definition at line 70 of file state_machine.h.

typedef boost::shared_ptr<MaterialUnloadServer> MaterialUnloadServerPtr

Definition at line 81 of file state_machine.h.

Definition at line 62 of file state_machine.h.

typedef boost::shared_ptr<MoveArmClient> MoveArmClientPtr

Definition at line 73 of file state_machine.h.

typedef actionlib::SimpleActionClient<object_manipulation_msgs::PickupAction> MovePickupClient

Definition at line 63 of file state_machine.h.

typedef boost::shared_ptr<MovePickupClient> MovePickupClientPtr

Definition at line 74 of file state_machine.h.

typedef actionlib::SimpleActionClient<object_manipulation_msgs::PlaceAction> MovePlaceClient

Definition at line 64 of file state_machine.h.

typedef boost::shared_ptr<MovePlaceClient> MovePlaceClientPtr

Definition at line 75 of file state_machine.h.



mtconnect_cnc_robot_example
Author(s): Jnicho
autogenerated on Mon Jan 6 2014 11:31:45