nav_pcontroller.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Ingo Kresse <kresse@in.tum.de>, U. Klank
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
62 #ifndef NAV_PCONTROLLER_H
63 #define NAV_PCONTROLLER_H
64 
65 #include <ros/ros.h>
66 #include <ros/time.h>
67 #include "tf/transform_listener.h"
69 
70 #include <string>
71 
72 #include <boost/thread.hpp>
73 
74 #include <geometry_msgs/PoseStamped.h>
75 #include <move_base_msgs/MoveBaseAction.h>
76 
77 #include "BaseDistance.h"
78 
80 private:
81 
87 
88  double vx_, vy_, vth_;
90  double x_now_, y_now_, th_now_;
92 
94 
95  std::string global_frame_;
96  std::string base_link_frame_;
97 
99 
104 
106 
107  boost::mutex lock;
108 
109  void newGoal(const geometry_msgs::PoseStamped &msg);
110  void newGoal(const geometry_msgs::PoseStamped::ConstPtr& msg);
111 
112  void cycle();
113  void stopRobot();
114  void sendVelCmd(double vx, double vy, double vth);
115  bool comparePoses(double x1, double y1, double a1,
116  double x2, double y2, double a2);
117 
118  bool retrieve_pose();
119  double p_control(double x, double p, double limit);
120  double limit_acc(double x, double x_old, double limit);
121  void compute_p_control();
122 
123  void parseParams();
124 
126 
127  void newMoveBaseGoal();
128  void preemptMoveBaseGoal();
129 
130 public:
131  BasePController();
133  void main();
134 };
135 
136 #endif
ros::Duration fail_timeout_
double p_control(double x, double p, double limit)
bool retrieve_pose()
retrieves tf pose and updates (x_now_, y_now_, th_now_)
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > move_base_actionserver_
double limit_acc(double x, double x_old, double limit)
BaseDistance dist_control_
void newGoal(const geometry_msgs::PoseStamped &msg)
double laser_watchdog_timeout_
ros::Subscriber sub_goal_
std::string global_frame_
ros::Publisher pub_vel_
tf::TransformListener tf_
boost::mutex lock
bool comparePoses(double x1, double y1, double a1, double x2, double y2, double a2)
ros::Time low_speed_time_
std::string base_link_frame_
ros::NodeHandle n_
void sendVelCmd(double vx, double vy, double vth)


nav_pcontroller
Author(s): Ingo Kresse
autogenerated on Thu Jun 6 2019 19:20:56