31 #include <geometry_msgs/Twist.h> 32 #include <sensor_msgs/Joy.h> 33 #include "boost/thread/mutex.hpp" 34 #include "boost/thread/thread.hpp" 43 void joyCallback(
const sensor_msgs::Joy::ConstPtr& joy);
86 geometry_msgs::Twist vel;
109 int main(
int argc,
char** argv)
111 ros::init(argc, argv,
"turtlebot_teleop");
void publish(const boost::shared_ptr< M > &message) const
geometry_msgs::Twist last_published_
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)
void joyCallback(const sensor_msgs::Joy::ConstPtr &joy)
int main(int argc, char **argv)
boost::mutex publish_mutex_
ROSCPP_DECL void spin(Spinner &spinner)
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
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool zero_twist_published_