37 #include <nav_msgs/Path.h> 68 dsrv_ =
new dynamic_reconfigure::Server<pose_follower::PoseFollowerConfig>(
70 dynamic_reconfigure::Server<pose_follower::PoseFollowerConfig>::CallbackType cb =
72 dsrv_->setCallback(cb);
103 base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x;
104 base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y;
105 base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z;
106 ROS_DEBUG(
"In the odometry callback with velocity values: (%.2f, %.2f, %.2f)",
112 double v1_x = x - pt_x;
113 double v1_y = y - pt_y;
114 double v2_x =
cos(heading);
115 double v2_y =
sin(heading);
117 double perp_dot = v1_x * v2_y - v1_y * v2_x;
118 double dot = v1_x * v2_x + v1_y * v2_y;
121 double vector_angle =
atan2(perp_dot, dot);
123 return -1.0 * vector_angle;
128 nav_msgs::Odometry base_odom;
146 nav_msgs::Path gui_path;
147 gui_path.poses.resize(path.size());
148 gui_path.header.frame_id = path[0].header.frame_id;
149 gui_path.header.stamp = path[0].header.stamp;
152 for (
unsigned int i = 0; i < path.size(); i++) {
153 gui_path.poses[i] = path[i];
160 geometry_msgs::PoseStamped robot_pose;
163 geometry_msgs::Twist empty_twist;
164 cmd_vel = empty_twist;
170 ROS_DEBUG(
"PoseFollower: current robot pose %f %f ==> %f", robot_pose.pose.position.x, robot_pose.pose.position.y,
tf2::getYaw(robot_pose.pose.orientation));
171 ROS_DEBUG(
"PoseFollower: target robot pose %f %f ==> %f", target_pose.pose.position.x, target_pose.pose.position.y,
tf2::getYaw(target_pose.pose.orientation));
174 geometry_msgs::Twist
diff =
diff2D(target_pose.pose, robot_pose.pose);
175 ROS_DEBUG(
"PoseFollower: diff %f %f ==> %f", diff.linear.x, diff.linear.y, diff.angular.z);
177 geometry_msgs::Twist limit_vel =
limitTwist(diff);
179 geometry_msgs::Twist test_vel = limit_vel;
182 double scaling_factor = 1.0;
183 double ds = scaling_factor /
samples_;
188 test_vel.linear.x = limit_vel.linear.x * scaling_factor;
189 test_vel.linear.y = limit_vel.linear.y * scaling_factor;
190 test_vel.angular.z = limit_vel.angular.z * scaling_factor;
196 scaling_factor -= ds;
201 ROS_ERROR(
"Not legal (%.2f, %.2f, %.2f)", limit_vel.linear.x, limit_vel.linear.y, limit_vel.angular.z);
202 geometry_msgs::Twist empty_twist;
203 cmd_vel = empty_twist;
210 bool in_goal_position =
false;
219 diff =
diff2D(target_pose.pose, robot_pose.pose);
224 in_goal_position =
true;
230 if(!in_goal_position)
235 geometry_msgs::Twist empty_twist;
236 cmd_vel = empty_twist;
246 ROS_ERROR(
"Could not transform the global plan to the frame of the controller");
260 const geometry_msgs::Pose& pose2_msg)
265 geometry_msgs::Twist res;
288 if(fabs(neg_yaw_diff) < fabs(yaw_diff)){
289 ROS_DEBUG(
"Negative is better: %.2f", neg_yaw_diff);
290 yaw_diff = neg_yaw_diff;
296 rot_diff.
setRPY(0.0, 0.0, yaw_diff);
301 diff = pose2.
inverse() * new_pose;
311 geometry_msgs::Twist res = twist;
330 double lin_overshoot =
sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y) /
max_vel_lin_;
331 double lin_undershoot =
min_vel_lin_ /
sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y);
332 if (lin_overshoot > 1.0)
334 res.linear.x /= lin_overshoot;
335 res.linear.y /= lin_overshoot;
339 if(lin_undershoot > 1.0)
341 res.linear.x *= lin_undershoot;
342 res.linear.y *= lin_undershoot;
347 if (std::isnan(res.linear.x))
349 if (std::isnan(res.linear.y))
359 ROS_DEBUG(
"Angular command %f", res.angular.z);
365 std::vector<geometry_msgs::PoseStamped>& transformed_plan){
366 const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
368 transformed_plan.clear();
371 if (global_plan.empty())
373 ROS_ERROR(
"Recieved plan with zero length");
377 geometry_msgs::TransformStamped transform;
379 plan_pose.header.frame_id, plan_pose.header.stamp,
380 plan_pose.header.frame_id);
385 geometry_msgs::PoseStamped newer_pose;
387 for(
unsigned int i = 0; i < global_plan.size(); ++i){
388 const geometry_msgs::PoseStamped& pose = global_plan[i];
390 tf_pose.
setData(tf_transform * tf_pose);
391 tf_pose.stamp_ = tf_transform.
stamp_;
392 tf_pose.frame_id_ = global_frame;
395 transformed_plan.push_back(newer_pose);
399 ROS_ERROR(
"No Transform available Error: %s\n", ex.what());
403 ROS_ERROR(
"Connectivity Error: %s\n", ex.what());
407 ROS_ERROR(
"Extrapolation Error: %s\n", ex.what());
408 if (!global_plan.empty())
409 ROS_ERROR(
"Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (
unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str());
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
ros::Publisher global_plan_pub_
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
ros::Subscriber odom_sub_
base_local_planner::TrajectoryPlannerROS collision_planner_
unsigned int current_waypoint_
bool turn_in_place_first_
ros::Time goal_reached_time_
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
double max_heading_diff_before_moving_
std::string getGlobalFrameID()
double trans_stopped_velocity_
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
bool transformGlobalPlan(const tf2_ros::Buffer &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2DROS &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
double headingDiff(double pt_x, double pt_y, double x, double y, double heading)
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan)
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
geometry_msgs::Twist diff2D(const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2)
std::vector< geometry_msgs::PoseStamped > global_plan_
double tolerance_timeout_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
void publish(const boost::shared_ptr< M > &message) const
void reconfigureCB(pose_follower::PoseFollowerConfig &config, uint32_t level)
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
bool getRobotPose(geometry_msgs::PoseStamped &global_pose) const
double in_place_trans_vel_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
double getYaw(const A &a)
double rot_stopped_velocity_
bool checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
dynamic_reconfigure::Server< pose_follower::PoseFollowerConfig > * dsrv_
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
void convert(const A &a, B &b)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
geometry_msgs::Twist limitTwist(const geometry_msgs::Twist &twist)
double min_in_place_vel_th_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
costmap_2d::Costmap2DROS * costmap_ros_
void setData(const T &input)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
nav_msgs::Odometry base_odom_