joyop.cpp
Go to the documentation of this file.
00001 
00006 #include <ecl/exceptions.hpp>
00007 #include <ecl/time.hpp>
00008 #include <geometry_msgs/Twist.h>
00009 #include <ros/ros.h>
00010 #include <sensor_msgs/Joy.h>
00011 #include <std_msgs/String.h>
00012 #include "boost/thread/mutex.hpp"
00013 #include "boost/thread/thread.hpp"
00014 
00015 
00016 namespace yocs_joyop
00017 {
00018 
00019 class JoyOp
00020 {
00021 public:
00022   JoyOp();
00023 
00024 private:
00025   void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
00026   void publish();
00027 
00028   ros::NodeHandle ph_, nh_;
00029 
00030   int linear_, angular_, deadman_button_, enable_button_, disable_button_, enabled_;
00031   double l_scale_, a_scale_, spin_freq_;
00032   ros::Publisher enable_pub_, disable_pub_, vel_pub_;
00033   ros::Subscriber joy_sub_;
00034 
00035   geometry_msgs::Twist last_published_;
00036   boost::mutex publish_mutex_;
00037   bool enable_pressed_, disable_pressed_, deadman_pressed_, zero_twist_published_, wait_for_connection_;
00038   ros::Timer timer_;
00039 
00040 };
00041 
00042 JoyOp::JoyOp():
00043   ph_("~"),
00044   linear_(1),
00045   angular_(0),
00046   deadman_button_(4),
00047   enable_button_(0),
00048   disable_button_(1),
00049   l_scale_(0.3),
00050   a_scale_(0.9),
00051   spin_freq_(10),
00052   wait_for_connection_(true)
00053 {
00054   ph_.param("linear_axis", linear_, linear_);
00055   ph_.param("angular_axis", angular_, angular_);
00056   ph_.param("deadman_button", deadman_button_, deadman_button_);
00057   ph_.param("enable_button", enable_button_, enable_button_);
00058   ph_.param("disable_button", disable_button_, disable_button_);
00059   ph_.param("angular_scale", a_scale_, a_scale_);
00060   ph_.param("linear_scale", l_scale_, l_scale_);
00061   ph_.param("spin_frequency", spin_freq_, spin_freq_);
00062   ph_.param("wait_for_connection", wait_for_connection_, wait_for_connection_);
00063 
00064   enabled_ = false;
00065   enable_pressed_ = false;
00066   disable_pressed_ = false;
00067   deadman_pressed_ = false;
00068   zero_twist_published_ = false;
00069 
00070   enable_pub_ = ph_.advertise<std_msgs::String>("enable", 1, true);
00071   disable_pub_ = ph_.advertise<std_msgs::String>("disable", 1, true);
00072   vel_pub_ = ph_.advertise<geometry_msgs::Twist>("cmd_vel", 1, true);
00073   joy_sub_ = nh_.subscribe<sensor_msgs::Joy>("joy", 10, &JoyOp::joyCallback, this);
00074 
00075   timer_ = nh_.createTimer(ros::Duration(1/spin_freq_), boost::bind(&JoyOp::publish, this));
00076 
00077   /*********************
00078    ** Wait for connection
00079    **********************/
00080   if (!wait_for_connection_)
00081   {
00082     return;
00083   }
00084   ecl::MilliSleep millisleep;
00085   int count = 0;
00086   bool connected = false;
00087   while (!connected)
00088   {
00089     if ((enable_pub_.getNumSubscribers() > 0) &&
00090         (disable_pub_.getNumSubscribers() > 0))
00091     {
00092       connected = true;
00093       break;
00094     }
00095     if (count == 6)
00096     {
00097       connected = false;
00098       break;
00099     }
00100     else
00101     {
00102       ROS_WARN_STREAM("JoyOp: Could not connect, trying again after 500ms...");
00103       try
00104       {
00105         millisleep(500);
00106       }
00107       catch (ecl::StandardException& e)
00108       {
00109         ROS_ERROR_STREAM("JoyOp: Waiting has been interrupted.");
00110         ROS_DEBUG_STREAM(e.what());
00111         return;
00112       }
00113       ++count;
00114     }
00115   }
00116   if (!connected)
00117   {
00118     ROS_ERROR("JoyOp: Could not connect.");
00119     ROS_ERROR("JoyOp: Check remappings for enable/disable topics.");
00120   }
00121   else
00122   {
00123     std_msgs::String msg;
00124     msg.data = "all";
00125     enable_pub_.publish(msg);
00126     ROS_INFO("JoyOp: connected.");
00127   }
00128 }
00129 
00130 void JoyOp::joyCallback(const sensor_msgs::Joy::ConstPtr& joy)
00131 {
00132   geometry_msgs::Twist vel;
00133   vel.angular.z = a_scale_*joy->axes[angular_];
00134   vel.linear.x = l_scale_*joy->axes[linear_];
00135   last_published_ = vel;
00136   deadman_pressed_ = joy->buttons[deadman_button_];
00137   enable_pressed_ = joy->buttons[enable_button_];
00138   disable_pressed_ = joy->buttons[disable_button_];
00139 }
00140 
00141 void JoyOp::publish()
00142 {
00143   boost::mutex::scoped_lock lock(publish_mutex_);
00144 
00145   if (enable_pressed_ && (!disable_pressed_))
00146   {
00147     if(!enabled_)
00148     {
00149       ROS_INFO_STREAM("JoyOp: Enabling motors.");
00150       std_msgs::String msg;
00151       msg.data = "all";
00152       enable_pub_.publish(msg);
00153       enabled_ = true;
00154     }
00155     else
00156     {
00157       ROS_WARN_STREAM("JoyOp: Motors have already been enabled.");
00158     }
00159   }
00160   else if (disable_pressed_)
00161   {
00162     if(enabled_)
00163     {
00164       ROS_INFO_STREAM("JoyOp: die, die, die (disabling motors).");
00165       std_msgs::String msg;
00166       msg.data = "all";
00167       enable_pub_.publish(msg);
00168       enabled_ = true;
00169     }
00170     else
00171     {
00172       ROS_WARN_STREAM("JoyOp: Motors have already been disabled.");
00173     }
00174     std_msgs::String msg;
00175     msg.data = "all";
00176     disable_pub_.publish(msg);
00177     enabled_ = false;
00178   }
00179 
00180   if (deadman_pressed_)
00181   {
00182     if (enabled_)
00183     {
00184       vel_pub_.publish(last_published_);
00185       zero_twist_published_=false;
00186     }
00187     else
00188     {
00189       ROS_WARN_STREAM_THROTTLE(1.0, "JoyOp: Motor system disabled. Won't send velocity commands.");
00190     }
00191   }
00192   else if(!deadman_pressed_ && !zero_twist_published_)
00193   {
00194     vel_pub_.publish(*new geometry_msgs::Twist());
00195     zero_twist_published_=true;
00196   }
00197 }
00198 
00199 } // namespace yocs_joyop
00200 
00201 int main(int argc, char** argv)
00202 {
00203   ros::init(argc, argv, "yocs_joyop");
00204   yocs_joyop::JoyOp joyop;
00205 
00206   ros::spin();
00207 }


yocs_joyop
Author(s): Marcus Liebhardt
autogenerated on Thu Jun 6 2019 21:47:19