jaco_pose_action.h
Go to the documentation of this file.
00001 
00046 #ifndef _JACO_POSE_ACTION_H_
00047 #define _JACO_POSE_ACTION_H_
00048 
00049 #include <ros/ros.h>
00050 #include "jaco_driver/jaco_comm.h"
00051 
00052 #include <actionlib/server/simple_action_server.h>
00053 #include <jaco_driver/ArmPoseAction.h>
00054 #include <tf/tf.h>
00055 #include <tf/transform_listener.h>
00056 
00057 namespace jaco
00058 {
00059 
00060 class JacoPoseActionServer
00061 {
00062         public:
00063         JacoPoseActionServer(JacoComm &, ros::NodeHandle &n);
00064         ~JacoPoseActionServer();
00065     void ActionCallback(const jaco_driver::ArmPoseGoalConstPtr &);
00066         
00067         private:
00068         JacoComm &arm;
00069     actionlib::SimpleActionServer<jaco_driver::ArmPoseAction> as_;
00070         tf::TransformListener listener;
00071 };
00072 
00073 }
00074 
00075 #endif // _JACO_POSE_ACTION_H_
00076 


jaco_driver
Author(s): Jeff Schmidt (Clearpath), Alex Bencz (Clearpath), Matt DeDonato (WPI)
autogenerated on Mon Jan 6 2014 11:23:43