00001 /********************************************************************* 00002 * 00003 * Copyright (c) 2013, Willow Garage, Inc. 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions 00008 * 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 00013 * copyright notice, this list of conditions and the following 00014 * disclaimer in the documentation and/or other materials provided 00015 * with the distribution. 00016 * * Neither the name of the Willow Garage nor the names of its 00017 * contributors may be used to endorse or promote products derived 00018 * from this software without specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 * POSSIBILITY OF SUCH DAMAGE. 00032 *********************************************************************/ 00033 00034 00035 #include "arm_mover.h" 00036 00037 #include <geometry_msgs/PoseStamped.h> 00038 00039 ArmMover::ArmMover( ros::NodeHandle pnh ) 00040 { 00041 joy_sub_ = nh_.subscribe<sensor_msgs::Joy>( "joy", 1, boost::bind(&ArmMover::joyCb, this, _1) ); 00042 00043 command_pub_ = nh_.advertise<geometry_msgs::PoseStamped>( "command", 1 ); 00044 00045 pnh.param<std::string>( "tracked_frame", pose_msg_.header.frame_id, "" ); 00046 00047 pnh.param<int>( "deadman_button", deadman_button_, 0 ); 00048 00049 pnh.param<double>( "update_freq", update_freq_, 0.1 ); 00050 } 00051 00052 ArmMover::~ArmMover() 00053 { 00054 } 00055 00056 void ArmMover::joyCb( sensor_msgs::JoyConstPtr joy_msg ) 00057 { 00058 if ( ros::Time::now() - last_update_time_ < ros::Duration(update_freq_) ) 00059 { 00060 return; 00061 } 00062 00063 if ( joy_msg->buttons.size() <= deadman_button_ ) 00064 { 00065 ROS_ERROR_ONCE("Button index for deadman switch is out of bounds!"); 00066 return; 00067 } 00068 00069 if ( joy_msg->buttons.at(deadman_button_) ) 00070 { 00071 last_update_time_ = ros::Time::now(); 00072 pose_msg_.header.stamp = ros::Time::now(); 00073 pose_msg_.pose.orientation.w = 1; 00074 command_pub_.publish( pose_msg_ ); 00075 } 00076 }