38 #include <tf2/LinearMath/Matrix3x3.h>
39 #include <tf2/utils.h>
40 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
42 #define GOAL_ATTRIBUTE_UNUSED
44 #define GOAL_ATTRIBUTE_UNUSED __attribute__ ((unused))
50 return hypot(goal_x - global_pose.pose.position.x, goal_y - global_pose.pose.position.y);
54 double yaw = tf2::getYaw(global_pose.pose.orientation);
55 return angles::shortest_angular_distance(yaw, goal_th);
64 nav_msgs::Path gui_path;
65 gui_path.poses.resize(path.
size());
66 gui_path.header.frame_id = path[0].header.frame_id;
67 gui_path.header.stamp = path[0].header.stamp;
70 for(
unsigned int i=0; i < path.
size(); i++){
71 gui_path.poses[i] = path[i];
74 pub.publish(gui_path);
78 ROS_ASSERT(global_plan.
size() >= plan.
size());
79 double min_plan_sq_dist = 1e6;
80 int current_waypoint_index = -1;
82 for(
unsigned int i = 0; i < plan.
size(); ++i){
83 double x_diff = global_pose.pose.position.x - plan[i].pose.position.x;
84 double y_diff = global_pose.pose.position.y - plan[i].pose.position.y;
85 double sq_plan_dist = x_diff * x_diff + y_diff * y_diff;
87 if (sq_plan_dist < min_plan_sq_dist){
88 current_waypoint_index = i;
89 min_plan_sq_dist = sq_plan_dist;
94 if (current_waypoint_index >= 0)
96 ROS_DEBUG(
"Nearest waypoint to <%f, %f> is <%f, %f>\n", global_pose.pose.position.x, global_pose.pose.position.y,
97 plan[current_waypoint_index].pose.position.x, plan[current_waypoint_index].pose.position.y);
104 double waypoint_dist_sum = 0;
105 unsigned int target_waypoint_index = plan.
size() - 1;
106 for(
unsigned int i = 1; i < plan.
size(); ++i){
107 double x_diff = plan[i].pose.position.x - plan[i-1].pose.position.x;
108 double y_diff = plan[i].pose.position.y - plan[i-1].pose.position.y;
109 double waypoint_dist = sqrt(x_diff * x_diff + y_diff * y_diff);
110 waypoint_dist_sum += waypoint_dist;
111 if (waypoint_dist_sum > lookahead)
113 target_waypoint_index = i;
122 const tf2_ros::Buffer& tf,
124 const geometry_msgs::PoseStamped& global_pose,
128 transformed_plan.
clear();
130 if (global_plan.
empty()) {
131 ROS_ERROR(
"Received plan with zero length");
135 const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
138 geometry_msgs::TransformStamped plan_to_global_transform = tf.lookupTransform(global_frame, ros::Time(),
139 plan_pose.header.frame_id, plan_pose.header.stamp, plan_pose.header.frame_id, ros::Duration(0.5));
142 geometry_msgs::PoseStamped robot_pose;
143 tf.transform(global_pose, robot_pose, plan_pose.header.frame_id);
150 double sq_dist_threshold = dist_threshold * dist_threshold;
154 while(i < (
unsigned int)global_plan.
size()) {
155 double x_diff = robot_pose.pose.position.x - global_plan[i].pose.position.x;
156 double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y;
157 sq_dist = x_diff * x_diff + y_diff * y_diff;
158 if (sq_dist <= sq_dist_threshold) {
164 geometry_msgs::PoseStamped newer_pose;
167 while(i < (
unsigned int)global_plan.
size() && sq_dist <= sq_dist_threshold) {
168 const geometry_msgs::PoseStamped& pose = global_plan[i];
169 tf2::doTransform(pose, newer_pose, plan_to_global_transform);
173 double x_diff = robot_pose.pose.position.x - global_plan[i].pose.position.x;
174 double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y;
175 sq_dist = x_diff * x_diff + y_diff * y_diff;
180 catch(tf2::LookupException& ex) {
181 ROS_ERROR(
"No Transform available Error: %s\n", ex.what());
184 catch(tf2::ConnectivityException& ex) {
185 ROS_ERROR(
"Connectivity Error: %s\n", ex.what());
188 catch(tf2::ExtrapolationException& ex) {
189 ROS_ERROR(
"Extrapolation Error: %s\n", ex.what());
190 if (!global_plan.
empty())
191 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());
201 const std::string& global_frame, geometry_msgs::PoseStamped &goal_pose) {
202 if (global_plan.
empty())
204 ROS_ERROR(
"Received plan with zero length");
208 const geometry_msgs::PoseStamped& plan_goal_pose = global_plan.
back();
210 geometry_msgs::TransformStamped transform = tf.lookupTransform(global_frame, ros::Time(),
211 plan_goal_pose.header.frame_id, plan_goal_pose.header.stamp,
212 plan_goal_pose.header.frame_id, ros::Duration(0.5));
214 tf2::doTransform(plan_goal_pose, goal_pose, transform);
216 catch(tf2::LookupException& ex) {
217 ROS_ERROR(
"No Transform available Error: %s\n", ex.what());
220 catch(tf2::ConnectivityException& ex) {
221 ROS_ERROR(
"Connectivity Error: %s\n", ex.what());
224 catch(tf2::ExtrapolationException& ex) {
225 ROS_ERROR(
"Extrapolation Error: %s\n", ex.what());
226 if (global_plan.
size() > 0)
227 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());
238 geometry_msgs::PoseStamped& global_pose,
239 const nav_msgs::Odometry& base_odom,
240 double rot_stopped_vel,
double trans_stopped_vel,
241 double xy_goal_tolerance,
double yaw_goal_tolerance){
244 geometry_msgs::PoseStamped goal_pose;
245 getGoalPose(tf, global_plan, global_frame, goal_pose);
247 double goal_x = goal_pose.pose.position.x;
248 double goal_y = goal_pose.pose.position.y;
249 double goal_th = tf2::getYaw(goal_pose.pose.orientation);
256 if(
stopped(base_odom, rot_stopped_vel, trans_stopped_vel))
264 bool stopped(
const nav_msgs::Odometry& base_odom,
265 const double& rot_stopped_velocity,
const double& trans_stopped_velocity){
266 return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity
267 && fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity
268 && fabs(base_odom.twist.twist.linear.y) <= trans_stopped_velocity;
271 bool stopped(
const geometry_msgs::PoseStamped& robot_vel,
const double& rot_stopped_velocity,
const double& trans_stopped_velocity){
272 nav_msgs::Odometry base_odom;
273 base_odom.twist.twist.linear.x = robot_vel.pose.position.x;
274 base_odom.twist.twist.linear.y = robot_vel.pose.position.y;
275 base_odom.twist.twist.angular.z = tf2::getYaw(robot_vel.pose.orientation);
276 return stopped(base_odom, rot_stopped_velocity, trans_stopped_velocity);