33 #include <move_base_msgs/MoveBaseAction.h> 34 #include <nav_msgs/Path.h> 52 void cbPath(
const nav_msgs::Path::ConstPtr& msg)
73 move_base_msgs::MoveBaseGoal goal;
75 if (path_.poses.size() <=
pos_)
77 ROS_WARN(
"Patrol finished. Waiting next path.");
83 goal.target_pose.header = path_.poses[
pos_].header;
85 goal.target_pose.pose = path_.poses[
pos_].pose;
87 act_cli_->sendGoal(goal);
101 if (path_.poses.size() == 0)
115 ROS_INFO(
"Action has been finished.");
120 ROS_ERROR(
"Action has been aborted. Skipping.");
131 int main(
int argc,
char** argv)
void cbPath(const nav_msgs::Path::ConstPtr &msg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::shared_ptr< MoveBaseClient > act_cli_
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
#define ROS_WARN_ONCE(...)
ros::Subscriber sub_path_
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient