Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #ifndef KATANA_TELEOP_PS3_H__
00026 #define KATANA_TELEOP_PS3_H__
00027
00028 #include <ros/ros.h>
00029 #include <sensor_msgs/Joy.h>
00030 #include <sensor_msgs/JointState.h>
00031 #include <geometry_msgs/PoseStamped.h>
00032 #include <kinematics_msgs/GetPositionFK.h>
00033 #include <kinematics_msgs/GetConstraintAwarePositionIK.h>
00034 #include <kinematics_msgs/GetKinematicSolverInfo.h>
00035
00036 #include <katana_msgs/JointMovementAction.h>
00037 #include <actionlib/server/simple_action_server.h>
00038 #include <actionlib/client/simple_action_client.h>
00039
00040 typedef actionlib::SimpleActionClient<katana_msgs::JointMovementAction> JMAC;
00041
00042 namespace katana{
00043
00044 class KatanaTeleopPS3
00045 {
00046 public:
00047
00048 KatanaTeleopPS3();
00049
00050 bool matchJointGoalRequest();
00051 void addGripperGoalPosition(std::string name, float increment);
00052 bool getCurrentJointPosition(sensor_msgs::JointState &joint_state, std::string &name, float &position);
00053
00054 void jointStateCallback(const sensor_msgs::JointState::ConstPtr& js);
00055 void ps3joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
00056
00057 void loop();
00058
00059 ~KatanaTeleopPS3(){}
00060
00061 private:
00062
00063 bool active;
00064
00065 katana_msgs::JointMovementGoal goal;
00066 sensor_msgs::JointState currentState, savedState;
00067 geometry_msgs::PoseStamped currentPose, goalPose;
00068
00069 std::string ik_service, fk_service, ik_solver_info;
00070 ros::ServiceClient info_client, fk_client, ik_client;
00071
00072 ros::Subscriber js_sub_, ps3joy_sub;
00073
00074 JMAC action_client;
00075
00076 };
00077
00078 }
00079 #endif
00080