2 #include <sensor_msgs/Joy.h> 3 #include <std_srvs/Trigger.h> 4 #include <nav2d_operator/cmd.h> 29 void joyCB(
const sensor_msgs::Joy::ConstPtr& msg);
80 nav2d_operator::cmd cmd;
90 std_srvs::Trigger srv;
93 ROS_ERROR(
"Failed to send STOP_COMMAND to Navigator.");
100 std_srvs::Trigger srv;
103 ROS_ERROR(
"Failed to send PAUSE_COMMAND to Navigator.");
110 std_srvs::Trigger srv;
113 ROS_ERROR(
"Failed to send GETMAP_COMMAND to GetMap-Client.");
121 std_srvs::Trigger srv;
124 ROS_ERROR(
"Failed to send EXPLORE_COMMAND to Explore-Client.");
131 int main(
int argc,
char** argv)
ros::Subscriber mJoySubscriber
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
int mButtonPauseNavigator
#define NAV_PAUSE_SERVICE
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())
ros::Publisher mCommandPublisher
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
void joyCB(const sensor_msgs::Joy::ConstPtr &msg)
#define NAV_EXPLORE_SERVICE
int mButtonStartExploration
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceClient mPauseClient
ros::ServiceClient mExploreClient
int main(int argc, char **argv)
ros::ServiceClient mGetMapClient
ros::ServiceClient mStopClient
#define NAV_GETMAP_SERVICE