$search
00001 /* 00002 * Nao Joystick / Gamepad teleoperation 00003 * 00004 * Copyright 2009-2012 Armin Hornung, University of Freiburg 00005 * http://www.ros.org/wiki/nao_teleop 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions are met: 00009 * 00010 * * Redistributions of source code must retain the above copyright 00011 * notice, this list of conditions and the following disclaimer. 00012 * * Redistributions in binary form must reproduce the above copyright 00013 * notice, this list of conditions and the following disclaimer in the 00014 * documentation and/or other materials provided with the distribution. 00015 * * Neither the name of the University of Freiburg nor the names of its 00016 * contributors may be used to endorse or promote products derived from 00017 * this software without specific prior written permission. 00018 * 00019 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00020 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00021 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00022 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00023 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00024 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00025 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00026 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00027 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00028 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00029 * POSSIBILITY OF SUCH DAMAGE. 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 // switch between diamondback /electric: 00048 #if ROS_VERSION_MINIMUM(1,6,0) 00049 #include <sensor_msgs/Joy.h> 00050 using sensor_msgs::Joy; 00051 #else 00052 #include <joy/Joy.h> 00053 using joy::Joy; 00054 #endif 00055 00056 namespace nao_teleop{ 00062 class TeleopNaoJoy 00063 { 00064 public: 00065 TeleopNaoJoy(); 00066 void pubMsg(); 00067 ros::NodeHandle nh; 00068 ros::NodeHandle privateNh; 00069 00073 ros::Subscriber subscribeToJoystick(); 00074 00079 bool callBodyPoseClient(const std::string& poseName); 00080 00081 00082 protected: 00083 void joyCallback(const Joy::ConstPtr& joy); 00084 bool buttonPressed(int button, const Joy::ConstPtr& joy) const; 00085 bool buttonTriggered(int button, const Joy::ConstPtr& joy) const; 00086 bool buttonChanged(int button, const Joy::ConstPtr& joy, const Joy::ConstPtr& prevJoy) const; 00087 void initializePreviousJoystick(const Joy::ConstPtr& joy); 00088 void setPreviousJoystick(const Joy::ConstPtr& joy) { 00089 m_previousJoystick = joy; 00090 } 00091 00092 bool m_enabled; 00093 00094 00095 00100 template<class M, class T> 00101 ros::Subscriber subscribeToJoystick(void(T::*fp)(M), T* obj) { 00102 m_joySub = nh.subscribe<Joy>("joy", 3, fp,obj); 00103 return m_joySub; 00104 } 00105 00106 bool inhibitWalk(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& res); 00107 bool uninhibitWalk(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& res); 00108 bool axisValid(int axis, const Joy::ConstPtr& joy) const; 00109 00110 int m_xAxis; 00111 int m_yAxis; 00112 int m_turnAxis; 00113 int m_headYawAxis; 00114 int m_headPitchAxis; 00115 int m_crouchBtn; 00116 int m_initPoseBtn; 00117 int m_enableBtn; 00118 int m_modifyHeadBtn; 00119 int m_startScanBtn; 00120 int m_stopScanBtn; 00121 double m_maxVx; 00122 double m_maxVy; 00123 double m_maxVw; 00124 double m_maxHeadYaw; 00125 double m_maxHeadPitch; 00126 ros::Duration m_bodyPoseTimeOut; 00127 int m_inhibitCounter; 00128 00129 bool m_previousJoystick_initialized; 00130 Joy::ConstPtr m_previousJoystick; 00131 00132 ros::Publisher m_movePub; 00133 ros::Publisher m_moveBtnPub; 00134 ros::Publisher m_headPub; 00135 ros::Subscriber m_joySub; 00136 ros::Publisher m_speechPub; 00137 ros::ServiceServer m_inhibitWalkSrv; 00138 ros::ServiceServer m_uninhibitWalkSrv; 00139 ros::ServiceClient m_cmdVelClient; 00140 ros::ServiceClient m_stiffnessDisableClient; 00141 ros::ServiceClient m_stiffnessEnableClient; 00142 actionlib::SimpleActionClient<nao_msgs::BodyPoseAction> m_bodyPoseClient; 00143 geometry_msgs::Twist m_motion; 00144 nao_msgs::JointAnglesWithSpeed m_headAngles; 00145 }; 00146 } 00147 00148 #endif