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 #include <nao_teleop/teleop_nao_joy.h>
00033
00034 using sensor_msgs::Joy;
00035
00036 namespace nao_teleop{
00037 TeleopNaoJoy::TeleopNaoJoy()
00038 : privateNh("~"), m_enabled(false),
00039 m_xAxis(3), m_yAxis(2), m_turnAxis(0), m_headYawAxis(4), m_headPitchAxis(5),
00040 m_crouchBtn(9), m_initPoseBtn(0), m_enableBtn(8), m_modifyHeadBtn(5),
00041 m_maxVx(1.0), m_maxVy(1.0), m_maxVw(0.5),
00042 m_maxHeadYaw(2.0943), m_maxHeadPitch(0.7853),
00043 m_bodyPoseTimeOut(5.0),
00044 m_inhibitCounter(0), m_previousJoystick_initialized(false),
00045 m_bodyPoseClient("body_pose", true)
00046 {
00047 privateNh.param("axis_x", m_xAxis, m_xAxis);
00048 privateNh.param("axis_y", m_yAxis, m_yAxis);
00049 privateNh.param("axis_turn", m_turnAxis, m_turnAxis);
00050 privateNh.param("axis_head_yaw", m_headYawAxis, m_headYawAxis);
00051 privateNh.param("axis_head_pitch", m_headPitchAxis, m_headPitchAxis);
00052 privateNh.param("btn_crouch", m_crouchBtn, m_crouchBtn);
00053 privateNh.param("btn_init_pose", m_initPoseBtn, m_initPoseBtn);
00054 privateNh.param("btn_enable_control", m_enableBtn, m_enableBtn);
00055 privateNh.param("btn_head_mod", m_modifyHeadBtn, m_modifyHeadBtn);
00056 privateNh.param("max_vx", m_maxVx, m_maxVx);
00057 privateNh.param("max_vy", m_maxVy, m_maxVy);
00058 privateNh.param("max_vw", m_maxVw, m_maxVw);
00059
00060 privateNh.param("max_head_yaw", m_maxHeadYaw, m_maxHeadYaw);
00061 privateNh.param("max_head_pitch", m_maxHeadPitch, m_maxHeadPitch);
00062
00063 m_motion.linear.x = m_motion.linear.y = m_motion.angular.z = 0.0;
00064 m_headAngles.joint_names.push_back("HeadYaw");
00065 m_headAngles.joint_names.push_back("HeadPitch");
00066 m_headAngles.joint_angles.resize(2, 0.0f);
00067 m_headAngles.relative = 0;
00068 m_headAngles.speed = 0.2;
00069
00070 m_movePub = nh.advertise<geometry_msgs::Twist>("cmd_vel", 10);
00071 m_headPub = nh.advertise<nao_msgs::JointAnglesWithSpeed>("joint_angles", 1);
00072 m_speechPub = nh.advertise<std_msgs::String>("speech", 1);
00073 m_inhibitWalkSrv = nh.advertiseService("inhibit_walk", &TeleopNaoJoy::inhibitWalk, this);
00074 m_uninhibitWalkSrv = nh.advertiseService("uninhibit_walk", &TeleopNaoJoy::uninhibitWalk, this);
00075 m_cmdVelClient = nh.serviceClient<nao_msgs::CmdVelService>("cmd_vel_srv");
00076 m_stiffnessDisableClient = nh.serviceClient<std_srvs::Empty>("body_stiffness/disable");
00077 m_stiffnessEnableClient = nh.serviceClient<std_srvs::Empty>("body_stiffness/enable");
00078
00079
00080 if (!m_bodyPoseClient.waitForServer(ros::Duration(3.0))){
00081 ROS_WARN_STREAM("Could not connect to \"body_pose\" action server, "
00082 << "there will be no body poses available on button presses.\n"
00083 << "Is the pose_manager node running?");
00084 }
00085
00086 }
00087
00088
00089 ros::Subscriber TeleopNaoJoy::subscribeToJoystick() {
00090 return subscribeToJoystick(&TeleopNaoJoy::joyCallback, this);
00091 }
00092
00093 bool TeleopNaoJoy::callBodyPoseClient(const std::string& poseName){
00094 if (!m_bodyPoseClient.isServerConnected()){
00095 return false;
00096 }
00097
00098 nao_msgs::BodyPoseGoal goal;
00099 goal.pose_name = poseName;
00100 m_bodyPoseClient.sendGoalAndWait(goal, m_bodyPoseTimeOut);
00101 actionlib::SimpleClientGoalState state = m_bodyPoseClient.getState();
00102 if (state != actionlib::SimpleClientGoalState::SUCCEEDED){
00103 ROS_ERROR("Pose action \"%s\" did not succeed (%s): %s", goal.pose_name.c_str(), state.toString().c_str(), state.text_.c_str());
00104 return false;
00105 } else{
00106 ROS_INFO("Pose action \"%s\" succeeded", goal.pose_name.c_str());
00107 return true;
00108 }
00109
00110 }
00111
00112
00113 void TeleopNaoJoy::initializePreviousJoystick(const Joy::ConstPtr& joy) {
00114 if(!m_previousJoystick_initialized) {
00115
00116
00117
00118 Joy::Ptr pJoy(new Joy());
00119 pJoy->buttons.resize( joy->buttons.size(), 0);
00120 pJoy->axes.resize( joy->axes.size(), 0.0);
00121 m_previousJoystick = pJoy;
00122 m_previousJoystick_initialized = true;
00123 }
00124
00125 }
00126
00127
00133 void TeleopNaoJoy::joyCallback(const Joy::ConstPtr& joy){
00134 initializePreviousJoystick(joy);
00135
00136
00137
00138
00139 if (m_enabled && buttonTriggered(m_crouchBtn, joy) && m_bodyPoseClient.isServerConnected()){
00140 if (callBodyPoseClient("crouch")){
00141 std_srvs::Empty e;
00142 m_stiffnessDisableClient.call(e);
00143 }
00144 }
00145
00146 if (m_enabled && buttonTriggered(m_initPoseBtn, joy) && m_bodyPoseClient.isServerConnected()){
00147 callBodyPoseClient("init");
00148 }
00149
00150 if (buttonTriggered(m_enableBtn, joy)){
00151 std_msgs::String string;
00152 if (m_enabled){
00153 m_enabled = false;
00154 string.data = "Gamepad control disabled";
00155
00156 } else{
00157 m_enabled = true;
00158 string.data = "Gamepad control enabled";
00159 std_srvs::Empty e;
00160 m_stiffnessEnableClient.call(e);
00161 }
00162 m_speechPub.publish(string);
00163 ROS_INFO("%s", (string.data).c_str());
00164
00165 }
00166
00167
00168
00169
00170 if (!axisValid(m_xAxis, joy) || !axisValid(m_yAxis, joy) || !axisValid(m_turnAxis, joy)){
00171 m_motion.linear.x = m_motion.linear.y = m_motion.angular.z = 0.0;
00172 m_headAngles.joint_angles[0] = m_headAngles.joint_angles[1] = 0.0;
00173 ROS_WARN("Joystick message too short for Move or Turn axis!\n");
00174 } else{
00175 if (buttonPressed(m_modifyHeadBtn, joy)){
00176
00177 m_headAngles.header.stamp = ros::Time::now();
00178 m_headAngles.relative = 1;
00179 m_headAngles.joint_angles[0] = joy->axes[m_turnAxis];
00180 m_headAngles.joint_angles[1] = joy->axes[m_xAxis];
00181
00182 } else {
00183
00184 m_headAngles.joint_angles[0] = m_headAngles.joint_angles[1] = 0.0;
00185
00186 m_motion.linear.x = m_maxVx * std::max(std::min(joy->axes[m_xAxis], 1.0f), -1.0f);
00187 m_motion.linear.y = m_maxVy * std::max(std::min(joy->axes[m_yAxis], 1.0f), -1.0f);
00188 m_motion.angular.z = m_maxVw * std::max(std::min(joy->axes[m_turnAxis], 1.0f), -1.0f);
00189 }
00190 }
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205 setPreviousJoystick(joy);
00206
00207 }
00208
00216 bool TeleopNaoJoy::buttonPressed(int button, const Joy::ConstPtr& joy) const{
00217 return (button >= 0 && unsigned(button) < joy->buttons.size() && joy->buttons[button] == 1);
00218 }
00219
00227 bool TeleopNaoJoy::buttonTriggered(int button, const Joy::ConstPtr& joy) const{
00228 return (buttonPressed(button, joy) && buttonChanged(button, joy, m_previousJoystick));
00229 }
00230
00231
00232
00242 bool TeleopNaoJoy::buttonChanged(int button, const Joy::ConstPtr& joy, const Joy::ConstPtr& prevJoy) const{
00243 return (unsigned(button) < joy->buttons.size() && joy->buttons[button] != prevJoy->buttons[button] );
00244 }
00245
00253 bool TeleopNaoJoy::axisValid(int axis, const Joy::ConstPtr& joy) const{
00254 return (axis >= 0 && unsigned(axis) < joy->buttons.size());
00255 }
00256
00260 void TeleopNaoJoy::pubMsg(){
00261 if (m_enabled && m_inhibitCounter == 0) {
00262 m_movePub.publish(m_motion);
00263 m_headPub.publish(m_headAngles);
00264 }
00265 }
00266
00279 bool TeleopNaoJoy::inhibitWalk(std_srvs::EmptyRequest& , std_srvs::EmptyResponse& res) {
00280 if(m_inhibitCounter == 0) {
00281
00282 m_motion.linear.x = 0.0;
00283 m_motion.linear.y = 0.0;
00284 m_motion.linear.z = 0.0;
00285 m_motion.angular.x = 0.0;
00286 m_motion.angular.y = 0.0;
00287 m_motion.angular.z = 0.0;
00288 nao_msgs::CmdVelService service_call;
00289 service_call.request.twist = m_motion;
00290 m_cmdVelClient.call(service_call);
00291 }
00292 m_inhibitCounter++;
00293 ROS_DEBUG("Inhibit counter: %d", m_inhibitCounter);
00294 return true;
00295 }
00296
00307 bool TeleopNaoJoy::uninhibitWalk(std_srvs::EmptyRequest &req, std_srvs::EmptyResponse& res) {
00308 if(m_inhibitCounter > 0) {
00309 m_inhibitCounter--;
00310 ROS_DEBUG("Inhibit counter: %d", m_inhibitCounter);
00311 } else {
00312 m_inhibitCounter = 0;
00313 ROS_WARN("/uninhibit_walk called more times than /inhibit_walk - ignoring");
00314 }
00315 return true;
00316 }
00317 }
00318