8 #include <geometry_msgs/Twist.h>    10 #include <sensor_msgs/Joy.h>    11 #include <std_msgs/String.h>    12 #include "boost/thread/mutex.hpp"    13 #include "boost/thread/thread.hpp"    25   void joyCallback(
const sensor_msgs::Joy::ConstPtr& joy);
    90   ecl::MilliSleep millisleep;
    92   bool connected = 
false;
    96         (disable_pub_.getNumSubscribers() > 0))
   108       ROS_WARN_STREAM(
"JoyOp: Could not connect, trying again after 500ms...");
   125     ROS_ERROR(
"JoyOp: Check remappings for enable/disable topics.");
   129     std_msgs::String 
msg;
   138   geometry_msgs::Twist vel;
   156       std_msgs::String 
msg;
   171       std_msgs::String 
msg;
   180     std_msgs::String 
msg;
   207 int main(
int argc, 
char** argv)
 
void publish(const boost::shared_ptr< M > &message) const 
const char * what() const 
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::mutex publish_mutex_
ros::Publisher enable_pub_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const 
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
ros::Publisher disable_pub_
#define ROS_WARN_STREAM_THROTTLE(rate, args)
uint32_t getNumSubscribers() const 
#define ROS_INFO_STREAM(args)
bool zero_twist_published_
geometry_msgs::Twist last_published_
#define ROS_ERROR_STREAM(args)
void joyCallback(const sensor_msgs::Joy::ConstPtr &joy)