35 #include <move_base_msgs/MoveBaseAction.h> 36 #include <planner_cspace_msgs/MoveWithToleranceAction.h> 37 #include <nav_msgs/Path.h> 61 void cbPath(
const nav_msgs::Path::ConstPtr& msg)
77 pnh_.
param(
"with_tolerance", with_tolerance_,
false);
78 pnh_.
param(
"tolerance_lin", tolerance_lin_, 0.1);
79 pnh_.
param(
"tolerance_ang", tolerance_ang_, 0.1);
80 pnh_.
param(
"tolerance_ang_finish", tolerance_ang_finish_, 0.05);
95 if (path_.poses.size() <=
pos_)
97 ROS_WARN(
"Patrol finished. Waiting next path.");
105 planner_cspace_msgs::MoveWithToleranceGoal goal;
107 goal.target_pose.header = path_.poses[
pos_].header;
109 goal.target_pose.pose = path_.poses[
pos_].pose;
114 act_cli_tolerant_->sendGoal(goal);
118 move_base_msgs::MoveBaseGoal goal;
120 goal.target_pose.header = path_.poses[
pos_].header;
122 goal.target_pose.pose = path_.poses[
pos_].pose;
124 act_cli_->sendGoal(goal);
139 if (path_.poses.size() == 0)
152 act_cli_tolerant_->getState() :
153 act_cli_->getState();
156 ROS_INFO(
"Action has been finished.");
161 ROS_ERROR(
"Action has been aborted. Skipping.");
172 int main(
int argc,
char** argv)
void cbPath(const nav_msgs::Path::ConstPtr &msg)
std::shared_ptr< MoveWithToleranceClient > act_cli_tolerant_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::shared_ptr< MoveBaseClient > act_cli_
actionlib::SimpleActionClient< planner_cspace_msgs::MoveWithToleranceAction > MoveWithToleranceClient
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(...)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
double tolerance_ang_finish_
ros::Subscriber sub_path_
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient