32 #include <pr2_controllers_msgs/Pr2GripperCommand.h> 33 #include <sensor_msgs/Joy.h> 51 pub_ =
nh_.
advertise<pr2_controllers_msgs::Pr2GripperCommand>(
"command", 1,
false);
96 int main(
int argc,
char** argv)
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())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
pr2_controllers_msgs::Pr2GripperCommand open_cmd_
pr2_controllers_msgs::Pr2GripperCommand close_cmd_
void joyCallback(const sensor_msgs::JoyConstPtr &joy)