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
00026
00027
00028
00029
00030
00031
00032
00033 #ifndef NAO_TELEOP_TELEOP_NAO_JOY_
00034 #define NAO_TELEOP_TELEOP_NAO_JOY_
00035
00036 #include <ros/ros.h>
00037 #include <std_msgs/String.h>
00038 #include <geometry_msgs/Twist.h>
00039 #include <std_srvs/Empty.h>
00040 #include <nao_msgs/JointAnglesWithSpeed.h>
00041 #include <nao_msgs/JointTrajectoryAction.h>
00042 #include <nao_msgs/BodyPoseAction.h>
00043 #include <nao_msgs/BodyPoseActionGoal.h>
00044 #include <nao_msgs/CmdVelService.h>
00045 #include <actionlib/client/simple_action_client.h>
00046
00047 #include <sensor_msgs/Joy.h>
00048
00049
00050 namespace nao_teleop{
00056 class TeleopNaoJoy
00057 {
00058 public:
00059 TeleopNaoJoy();
00060 void pubMsg();
00061 ros::NodeHandle nh;
00062 ros::NodeHandle privateNh;
00063
00067 ros::Subscriber subscribeToJoystick();
00068
00073 bool callBodyPoseClient(const std::string& poseName);
00074
00075
00076 protected:
00077 void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
00078 bool buttonPressed(int button, const sensor_msgs::Joy::ConstPtr& joy) const;
00079 bool buttonTriggered(int button, const sensor_msgs::Joy::ConstPtr& joy) const;
00080 bool buttonChanged(int button, const sensor_msgs::Joy::ConstPtr& joy, const sensor_msgs::Joy::ConstPtr& prevJoy) const;
00081 void initializePreviousJoystick(const sensor_msgs::Joy::ConstPtr& joy);
00082 void setPreviousJoystick(const sensor_msgs::Joy::ConstPtr& joy) {
00083 m_previousJoystick = joy;
00084 }
00085
00086 bool m_enabled;
00087
00088
00089
00094 template<class M, class T>
00095 ros::Subscriber subscribeToJoystick(void(T::*fp)(M), T* obj) {
00096 m_joySub = nh.subscribe<sensor_msgs::Joy>("joy", 3, fp,obj);
00097 return m_joySub;
00098 }
00099
00100 bool inhibitWalk(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& res);
00101 bool uninhibitWalk(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& res);
00102 bool axisValid(int axis, const sensor_msgs::Joy::ConstPtr& joy) const;
00103
00104 int m_xAxis;
00105 int m_yAxis;
00106 int m_turnAxis;
00107 int m_headYawAxis;
00108 int m_headPitchAxis;
00109 int m_crouchBtn;
00110 int m_initPoseBtn;
00111 int m_enableBtn;
00112 int m_modifyHeadBtn;
00113 int m_startScanBtn;
00114 int m_stopScanBtn;
00115 double m_maxVx;
00116 double m_maxVy;
00117 double m_maxVw;
00118 double m_maxHeadYaw;
00119 double m_maxHeadPitch;
00120 ros::Duration m_bodyPoseTimeOut;
00121 int m_inhibitCounter;
00122
00123 bool m_previousJoystick_initialized;
00124 sensor_msgs::Joy::ConstPtr m_previousJoystick;
00125
00126 ros::Publisher m_movePub;
00127 ros::Publisher m_moveBtnPub;
00128 ros::Publisher m_headPub;
00129 ros::Subscriber m_joySub;
00130 ros::Publisher m_speechPub;
00131 ros::ServiceServer m_inhibitWalkSrv;
00132 ros::ServiceServer m_uninhibitWalkSrv;
00133 ros::ServiceClient m_cmdVelClient;
00134 ros::ServiceClient m_stiffnessDisableClient;
00135 ros::ServiceClient m_stiffnessEnableClient;
00136 actionlib::SimpleActionClient<nao_msgs::BodyPoseAction> m_bodyPoseClient;
00137 geometry_msgs::Twist m_motion;
00138 nao_msgs::JointAnglesWithSpeed m_headAngles;
00139 };
00140 }
00141
00142 #endif