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 <naoqi_bridge_msgs/JointAnglesWithSpeed.h>
00041 #include <naoqi_bridge_msgs/BodyPoseAction.h>
00042 #include <actionlib/client/simple_action_client.h>
00043
00044 #include <sensor_msgs/Joy.h>
00045
00046
00047 namespace nao_teleop{
00053 class TeleopNaoJoy
00054 {
00055 public:
00056 TeleopNaoJoy();
00057 void pubMsg();
00058 ros::NodeHandle nh;
00059 ros::NodeHandle privateNh;
00060
00064 ros::Subscriber subscribeToJoystick();
00065
00070 bool callBodyPoseClient(const std::string& poseName);
00071
00072
00073 protected:
00074 void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
00075 bool buttonPressed(int button, const sensor_msgs::Joy::ConstPtr& joy) const;
00076 bool buttonTriggered(int button, const sensor_msgs::Joy::ConstPtr& joy) const;
00077 bool buttonChanged(int button, const sensor_msgs::Joy::ConstPtr& joy, const sensor_msgs::Joy::ConstPtr& prevJoy) const;
00078 void initializePreviousJoystick(const sensor_msgs::Joy::ConstPtr& joy);
00079 void setPreviousJoystick(const sensor_msgs::Joy::ConstPtr& joy) {
00080 m_previousJoystick = joy;
00081 }
00082
00083 bool m_enabled;
00084
00085
00086
00091 template<class M, class T>
00092 ros::Subscriber subscribeToJoystick(void(T::*fp)(M), T* obj) {
00093 m_joySub = nh.subscribe<sensor_msgs::Joy>("joy", 3, fp,obj);
00094 return m_joySub;
00095 }
00096
00097 bool inhibitWalk(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& res);
00098 bool uninhibitWalk(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& res);
00099 bool axisValid(int axis, const sensor_msgs::Joy::ConstPtr& joy) const;
00100
00101 int m_xAxis;
00102 int m_yAxis;
00103 int m_turnAxis;
00104 int m_headYawAxis;
00105 int m_headPitchAxis;
00106 int m_crouchBtn;
00107 int m_initPoseBtn;
00108 int m_enableBtn;
00109 int m_modifyHeadBtn;
00110 double m_maxVx;
00111 double m_maxVy;
00112 double m_maxVw;
00113 double m_maxHeadYaw;
00114 double m_maxHeadPitch;
00115 bool m_prevMotionZero;
00116 bool m_prevHeadZero;
00117 ros::Duration m_bodyPoseTimeOut;
00118 int m_inhibitCounter;
00119
00120 bool m_previousJoystick_initialized;
00121 sensor_msgs::Joy::ConstPtr m_previousJoystick;
00122
00123 ros::Publisher m_movePub;
00124 ros::Publisher m_moveBtnPub;
00125 ros::Publisher m_headPub;
00126 ros::Subscriber m_joySub;
00127 ros::Publisher m_speechPub;
00128 ros::ServiceServer m_inhibitWalkSrv;
00129 ros::ServiceServer m_uninhibitWalkSrv;
00130 ros::ServiceClient m_cmdVelClient;
00131 ros::ServiceClient m_stiffnessDisableClient;
00132 ros::ServiceClient m_stiffnessEnableClient;
00133 actionlib::SimpleActionClient<naoqi_bridge_msgs::BodyPoseAction> m_bodyPoseClient;
00134 geometry_msgs::Twist m_motion;
00135 naoqi_bridge_msgs::JointAnglesWithSpeed m_headAngles;
00136 };
00137 }
00138
00139 #endif