45 MoveSlowAndClear::MoveSlowAndClear():global_costmap_(NULL), local_costmap_(NULL),
46 initialized_(false), remove_limit_thread_(NULL), limit_set_(false){}
66 std::string planner_namespace;
67 private_nh_.
param(
"planner_namespace", planner_namespace, std::string(
"DWAPlannerROS"));
77 ROS_ERROR(
"This recovery behavior has not been initialized, doing nothing.");
80 ROS_WARN(
"Move slow and clear recovery behavior started.");
85 std::vector<geometry_msgs::Point> global_poly, local_poly;
86 geometry_msgs::Point pt;
88 for(
int i = -1; i <= 1; i+=2)
92 global_poly.push_back(pt);
96 global_poly.push_back(pt);
100 local_poly.push_back(pt);
104 local_poly.push_back(pt);
111 if(plugin->getName().find(
"obstacles")!=std::string::npos){
121 if(plugin->getName().find(
"obstacles")!=std::string::npos){
129 boost::mutex::scoped_lock l(
mutex_);
158 double x1 = global_pose.getOrigin().x();
159 double y1 = global_pose.getOrigin().y();
164 return (x2 - x1) * (x2 - x1) + (y2 - y1) * (y2 - y1);
171 ROS_INFO(
"Moved far enough, removing speed limit.");
186 boost::mutex::scoped_lock l(
mutex_);
195 dynamic_reconfigure::Reconfigure vel_reconfigure;
196 dynamic_reconfigure::DoubleParameter new_trans;
197 new_trans.name =
"max_trans_vel";
198 new_trans.value = trans_speed;
199 vel_reconfigure.request.config.doubles.push_back(new_trans);
205 ROS_ERROR(
"Something went wrong in the service call to dynamic_reconfigure");
209 dynamic_reconfigure::Reconfigure rot_reconfigure;
210 dynamic_reconfigure::DoubleParameter new_rot;
211 new_rot.name =
"max_rot_vel";
212 new_rot.value = rot_speed;
213 rot_reconfigure.request.config.doubles.push_back(new_rot);
219 ROS_ERROR(
"Something went wrong in the service call to dynamic_reconfigure");
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
costmap_2d::Costmap2DROS * local_costmap_
ros::NodeHandle private_nh_
tf::Stamped< tf::Pose > speed_limit_pose_
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
ros::Timer distance_check_timer_
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
bool call(MReq &req, MRes &res)
double limited_rot_speed_
void initialize(std::string n, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
Initialize the parameters of the behavior.
std::vector< boost::shared_ptr< Layer > > * getPlugins()
static const unsigned char FREE_SPACE
double limited_trans_speed_
void setRobotSpeed(double trans_speed, double rot_speed)
ros::NodeHandle planner_nh_
void distanceCheck(const ros::TimerEvent &e)
costmap_2d::Costmap2DROS * global_costmap_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void runBehavior()
Run the behavior.
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
const std::string & getNamespace() const
double clearing_distance_
ros::ServiceClient planner_dynamic_reconfigure_service_
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
LayeredCostmap * getLayeredCostmap()
boost::thread * remove_limit_thread_