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 #include <ros/ros.h>
00032 #include <pr2_controllers_msgs/Pr2GripperCommand.h>
00033 #include <sensor_msgs/Joy.h>
00034 
00035 class TeleopGripper
00036 {
00037 public:
00038   TeleopGripper()
00039   {
00040     ros::NodeHandle private_nh_("~");
00041 
00042     private_nh_.param("open_position",   open_cmd_.position,     0.08);
00043     private_nh_.param("open_max_effort", open_cmd_.max_effort,  -1.0);
00044 
00045     private_nh_.param("close_position",   close_cmd_.position,  -100.00);
00046     private_nh_.param("close_max_effort", close_cmd_.max_effort,   -1.0);
00047 
00048     private_nh_.param("open_button",   open_button_,   1);
00049     private_nh_.param("close_button",  close_button_,  2);
00050 
00051     pub_ = nh_.advertise<pr2_controllers_msgs::Pr2GripperCommand>("command", 1, false);
00052     sub_ = nh_.subscribe("joy", 1, &TeleopGripper::joyCallback, this);
00053 
00054     ROS_DEBUG("teleop_gripper started");
00055   }
00056 
00057   void joyCallback(const sensor_msgs::JoyConstPtr& joy)
00058   {
00059     ROS_DEBUG("Got a joy msg");
00060     if ((int) joy->buttons.size() <= open_button_ ||
00061         (int) joy->buttons.size() <= close_button_ ||
00062         open_button_ < 0 ||
00063         close_button_ < 0)
00064     {
00065       ROS_ERROR("Array lookup error: Joystick message has %u elems. Open Index [%u]. Close Index [%u]", (unsigned int)joy->buttons.size(), open_button_, close_button_);
00066       return;
00067     }
00068 
00069     ROS_DEBUG("open: Buttons[%u] = %u", open_button_, joy->buttons[open_button_]);
00070 
00071     if (joy->buttons[open_button_] == 1)
00072     {
00073       pub_.publish(open_cmd_);
00074       ROS_DEBUG("Opening");
00075     }
00076     else if (joy->buttons[close_button_] == 1)
00077     {
00078       pub_.publish(close_cmd_);
00079       ROS_DEBUG("Closing");
00080     }
00081   }
00082 
00083 private:
00084   ros::NodeHandle nh_;
00085   ros::Publisher pub_;
00086   ros::Subscriber sub_;
00087 
00088   int close_button_;
00089   int open_button_;
00090 
00091 
00092   pr2_controllers_msgs::Pr2GripperCommand open_cmd_;
00093   pr2_controllers_msgs::Pr2GripperCommand close_cmd_;
00094 };
00095 
00096 int main(int argc, char** argv)
00097 {
00098   ros::init(argc, argv, "teleop_gripper");
00099 
00100   TeleopGripper teleop_gripper;
00101 
00102   ros::spin();
00103 
00104 }