roch_joy.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <ros/ros.h>
00031 #include <geometry_msgs/Twist.h>
00032 #include <sensor_msgs/Joy.h>
00033 #include "boost/thread/mutex.hpp"
00034 #include "boost/thread/thread.hpp"
00035 #include "ros/console.h"
00036 
00037 class RochTeleop
00038 {
00039 public:
00040   RochTeleop();
00041 
00042 private:
00043   void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
00044   void publish();
00045 
00046   ros::NodeHandle ph_, nh_;
00047 
00048   int linear_, angular_, deadman_axis_;
00049   double l_scale_, a_scale_;
00050   ros::Publisher vel_pub_;
00051   ros::Subscriber joy_sub_;
00052 
00053   geometry_msgs::Twist last_published_;
00054   boost::mutex publish_mutex_;
00055   bool deadman_pressed_;
00056   bool zero_twist_published_;
00057   ros::Timer timer_;
00058 
00059 };
00060 
00061 RochTeleop::RochTeleop():
00062   ph_("~"),
00063   linear_(1),
00064   angular_(0),
00065   deadman_axis_(4),
00066   l_scale_(0.3),
00067   a_scale_(0.9)
00068 {
00069   ph_.param("axis_linear", linear_, linear_);
00070   ph_.param("axis_angular", angular_, angular_);
00071   ph_.param("axis_deadman", deadman_axis_, deadman_axis_);
00072   ph_.param("scale_angular", a_scale_, a_scale_);
00073   ph_.param("scale_linear", l_scale_, l_scale_);
00074 
00075   deadman_pressed_ = false;
00076   zero_twist_published_ = false;
00077 
00078   vel_pub_ = ph_.advertise<geometry_msgs::Twist>("cmd_vel", 1, true);
00079   joy_sub_ = nh_.subscribe<sensor_msgs::Joy>("joy", 10, &RochTeleop::joyCallback, this);
00080 
00081   timer_ = nh_.createTimer(ros::Duration(0.1), boost::bind(&RochTeleop::publish, this));
00082 }
00083 
00084 void RochTeleop::joyCallback(const sensor_msgs::Joy::ConstPtr& joy)
00085 { 
00086   geometry_msgs::Twist vel;
00087   vel.angular.z = a_scale_*joy->axes[angular_];
00088   vel.linear.x = l_scale_*joy->axes[linear_];
00089   last_published_ = vel;
00090   deadman_pressed_ = joy->buttons[deadman_axis_];
00091 }
00092 
00093 void RochTeleop::publish()
00094 {
00095   boost::mutex::scoped_lock lock(publish_mutex_);
00096 
00097   if (deadman_pressed_)
00098   {
00099     vel_pub_.publish(last_published_);
00100     zero_twist_published_=false;
00101   }
00102   else if(!deadman_pressed_ && !zero_twist_published_)
00103   {
00104     vel_pub_.publish(*new geometry_msgs::Twist());
00105     zero_twist_published_=true;
00106   }
00107 }
00108 
00109 int main(int argc, char** argv)
00110 {
00111   ros::init(argc, argv, "roch_teleop");
00112   RochTeleop roch_teleop;
00113 
00114   ros::spin();
00115 }


roch_teleop
Author(s): Chen
autogenerated on Thu Jun 6 2019 21:04:19