31 #include <sensor_msgs/Joy.h> 51 void cbJoy(
const sensor_msgs::Joy::Ptr msg)
54 if (msg->buttons[interrupt_button_])
74 "Use %s (%s%s) topic instead of %s (%s%s)",
81 pub_topic_ = msg->advertise(pnh_,
"output", 1,
false);
85 pub_topic_ = msg->advertise(nh_,
"mux_output", 1,
false);
99 sub_topics_[0] = neonavigation_common::compat::subscribe<topic_tools::ShapeShifter>(
102 sub_topics_[1] = neonavigation_common::compat::subscribe<topic_tools::ShapeShifter>(
106 pnh_.param(
"interrupt_button", interrupt_button_, 5);
107 pnh_.param(
"timeout", timeout_, 0.5);
128 int main(
int argc,
char* argv[])
std::string getSimplifiedNamespace(ros::NodeHandle &nh)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber sub_topics_[2]
void cbJoy(const sensor_msgs::Joy::Ptr msg)
ros::Publisher pub_topic_
void cbTopic(const boost::shared_ptr< topic_tools::ShapeShifter const > &msg, int id)
ROSCPP_DECL void spinOnce()
int main(int argc, char *argv[])