Classes | Namespaces | Typedefs | Variables
MoveArmActionClient.h File Reference
#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 <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 dependency graph for MoveArmActionClient.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::MoveArmActionClient

Namespaces

namespace  mtconnect_cnc_robot_example

Typedefs

typedef boost::tuple
< std::string, std::string,
tf::Transform
mtconnect_cnc_robot_example::CartesianGoal
typedef boost::shared_ptr
< planning_environment::CollisionModels
mtconnect_cnc_robot_example::CollisionModelsPtr
typedef boost::shared_ptr
< planning_models::KinematicState
mtconnect_cnc_robot_example::KinematicStatePtr
typedef boost::shared_ptr
< MoveArmActionClient > 
mtconnect_cnc_robot_example::MoveArmActionClientPtr
typedef
actionlib::SimpleActionClient
< arm_navigation_msgs::MoveArmAction
mtconnect_cnc_robot_example::MoveArmClient
typedef boost::shared_ptr
< MoveArmClient
mtconnect_cnc_robot_example::MoveArmClientPtr

Variables

static const std::string mtconnect_cnc_robot_example::DEFAULT_MOVE_ARM_ACTION = "move_arm_action"
static const double mtconnect_cnc_robot_example::DEFAULT_ORIENTATION_TOLERANCE = 0.02f
static const std::string mtconnect_cnc_robot_example::DEFAULT_PATH_MSG_TOPIC = "move_arm_path"
static const std::string mtconnect_cnc_robot_example::DEFAULT_PATH_PLANNER = "/ompl_planning/plan_kinematic_path"
static const int mtconnect_cnc_robot_example::DEFAULT_PATH_PLANNING_ATTEMPTS = 2
static const double mtconnect_cnc_robot_example::DEFAULT_PATH_PLANNING_TIME = 5.0f
static const std::string mtconnect_cnc_robot_example::DEFAULT_PLANNING_GROUPS_PARAMETER = "/robot_description_planning/groups"
static const std::string mtconnect_cnc_robot_example::DEFAULT_PLANNING_SCENE_DIFF_SERVICE = "/environment_server/set_planning_scene_diff"
static const double mtconnect_cnc_robot_example::DEFAULT_POSITION_TOLERANCE = 0.008f
static const double mtconnect_cnc_robot_example::DURATION_LOOP_PAUSE = 4.0f
static const double mtconnect_cnc_robot_example::DURATION_TIMER_CYCLE = 2.0f
static const double mtconnect_cnc_robot_example::DURATION_WAIT_RESULT = 80.0f
static const double mtconnect_cnc_robot_example::DURATION_WAIT_SERVER = 5.0f
static const int mtconnect_cnc_robot_example::MAX_WAIT_ATTEMPTS = 20
static const std::string mtconnect_cnc_robot_example::PARAM_ARM_GROUP = "arm_group"
static const std::string mtconnect_cnc_robot_example::PARAM_BASE_KEY = "base_link"
static const std::string mtconnect_cnc_robot_example::PARAM_GROUP_KEY = "name"
static const std::string mtconnect_cnc_robot_example::PARAM_TIP_KEY = "tip_link"


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