Go to the documentation of this file.
31 #include <sensor_msgs/Joy.h>
52 void cbJoy(
const sensor_msgs::Joy::Ptr msg)
57 "Out of range: number of buttons (%lu) must be greater than interrupt_button (%d).",
83 "Use %s (%s%s) topic instead of %s (%s%s)",
115 sub_topics_[0] = neonavigation_common::compat::subscribe<topic_tools::ShapeShifter>(
118 sub_topics_[1] = neonavigation_common::compat::subscribe<topic_tools::ShapeShifter>(
133 int main(
int argc,
char* argv[])
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void cbTopic(const boost::shared_ptr< topic_tools::ShapeShifter const > &msg, int id)
void cbTimer(const ros::TimerEvent &e)
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char *argv[])
std::string resolveName(const std::string &name, bool remap=true) const
ros::Publisher pub_topic_
ros::Subscriber sub_topics_[2]
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
T param(const std::string ¶m_name, const T &default_val) const
void cbJoy(const sensor_msgs::Joy::Ptr msg)
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
std::string getSimplifiedNamespace(ros::NodeHandle &nh)