34 #include <boost/bind.hpp> 39 #include <geometry_msgs/Twist.h> 46 return (x > 0) ? std::min(p*x, limit) :
std::max(p*x, -limit);
52 x = std::min(x, x_old + limit);
98 double tmp_fail_timeout;
99 n_.
param<
double>(
"fail_timeout", tmp_fail_timeout, 5.0);
117 double front, rear, left, right, tolerance;
119 n_.
param(
"speed_filter_name", stName, std::string(
"/speed_filter"));
120 n_.
param(stName +
"/footprint/left", left, 0.309);
121 n_.
param(stName +
"/footprint/right", right, -0.309);
122 n_.
param(stName +
"/footprint/front", front, 0.43);
123 n_.
param(stName +
"/footprint/rear", rear, -0.43);
124 n_.
param(stName +
"/footprint/tolerance", tolerance, 0.0);
145 boost::mutex::scoped_lock curr_lock(
lock);
154 boost::mutex::scoped_lock curr_lock(
lock);
156 geometry_msgs::PoseStamped goal;
166 ROS_WARN(
"no localization information yet %s",ex.what());
170 x_goal_ = goal.pose.position.x;
171 y_goal_ = goal.pose.position.y;
174 const geometry_msgs::Quaternion &q = goal.pose.orientation;
175 th_goal_ = atan2(q.x*q.y + q.w*q.z, 0.5 - q.y*q.y -q.z*q.z);
202 ROS_WARN(
"no localization information yet %s",ex.what());
212 th_now_ = atan2(q.x()*q.y() + q.w()*q.z(), 0.5 - q.y()*q.y() - q.z()*q.z());
225 if(th_diff > M_PI) th_diff = th_diff - 2*M_PI;
226 if(th_diff < -M_PI) th_diff = th_diff + 2*M_PI;
231 double dth = th_diff;
250 #define max(A,B) (A) > (B) ? (A) : (B) 254 boost::mutex::scoped_lock curr_lock(
lock);
302 move_base_msgs::MoveBaseFeedback feedback;
305 feedback.base_position.pose.position.x =
x_now_;
306 feedback.base_position.pose.position.y =
y_now_;
307 feedback.base_position.pose.position.z = 0.0;
313 #define ANG_NORM(a) atan2(sin((a)),cos((a))) 322 geometry_msgs::Twist cmdvel;
324 cmdvel.linear.x = vx;
325 cmdvel.linear.y = vy;
326 cmdvel.angular.z = vth;
333 double x2,
double y2,
double a2)
345 int main(
int argc,
char *argv[])
347 ros::init(argc, argv,
"nav_pcontroller");
boost::shared_ptr< const Goal > acceptNewGoal()
void publishFeedback(const FeedbackConstPtr &feedback)
ros::Duration fail_timeout_
double p_control(double x, double p, double limit)
void publish(const boost::shared_ptr< M > &message) const
bool fresh_scans(double watchdog_timeout)
Check if the laser scans are older than a certain timeout, to use with a watchdog.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool retrieve_pose()
retrieves tf pose and updates (x_now_, y_now_, th_now_)
void setFootprint(double front, double rear, double left, double right, double tolerance)
Sets front_, rear_, left_, right_, tolerance_, and early_reject_distance_.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void preemptMoveBaseGoal()
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > move_base_actionserver_
double limit_acc(double x, double x_old, double limit)
BaseDistance dist_control_
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
void newGoal(const geometry_msgs::PoseStamped &msg)
TFSIMD_FORCE_INLINE const tfScalar & x() const
double laser_watchdog_timeout_
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
ros::Subscriber sub_goal_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::string global_frame_
void registerPreemptCallback(boost::function< void()> cb)
TFSIMD_FORCE_INLINE const tfScalar & y() const
tf::TransformListener tf_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool comparePoses(double x1, double y1, double a1, double x2, double y2, double a2)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
void compute_distance_keeping(double *vx, double *vy, double *vth)
Sets vx_last_, vy_last and vth_last_ to input parameters, adjusting them.
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
ros::Time low_speed_time_
std::string base_link_frame_
void registerGoalCallback(boost::function< void()> cb)
void sendVelCmd(double vx, double vy, double vth)