48 #include <sensor_msgs/PointCloud2.h>
59 config.sim_granularity,
60 config.angular_sim_granularity,
88 int vx_samp, vy_samp, vth_samp;
89 vx_samp = config.vx_samples;
90 vy_samp = config.vy_samples;
91 vth_samp = config.vth_samples;
94 ROS_WARN(
"You've specified that you don't want any samples in the x dimension. We'll at least assume that you want to sample one value... so we're going to set vx_samples to 1 instead");
96 config.vx_samples = vx_samp;
100 ROS_WARN(
"You've specified that you don't want any samples in the y dimension. We'll at least assume that you want to sample one value... so we're going to set vy_samples to 1 instead");
102 config.vy_samples = vy_samp;
106 ROS_WARN(
"You've specified that you don't want any samples in the th dimension. We'll at least assume that you want to sample one value... so we're going to set vth_samples to 1 instead");
108 config.vth_samples = vth_samp;
119 planner_util_(planner_util),
120 obstacle_costs_(planner_util->getCostmap()),
121 path_costs_(planner_util->getCostmap()),
122 goal_costs_(planner_util->getCostmap(), 0.0, 0.0, true),
123 goal_front_costs_(planner_util->getCostmap(), 0.0, 0.0, true),
124 alignment_costs_(planner_util->getCostmap())
134 std::string controller_frequency_param_name;
135 if(!private_nh.searchParam(
"controller_frequency", controller_frequency_param_name)) {
138 double controller_frequency = 0;
139 private_nh.param(controller_frequency_param_name, controller_frequency, 20.0);
140 if(controller_frequency > 0) {
143 ROS_WARN(
"A controller_frequency less than 0 has been set. Ignoring the parameter, assuming a rate of 20Hz");
152 private_nh.param(
"sum_scores", sum_scores,
false);
159 [
this](
int cx,
int cy,
float &path_cost,
float &goal_cost,
float &occ_cost,
float &total_cost){
160 return getCellCosts(cx, cy, path_cost, goal_cost, occ_cost, total_cost);
163 private_nh.param(
"global_frame_id",
frame_id_, std::string(
"odom"));
165 traj_cloud_pub_ = private_nh.advertise<sensor_msgs::PointCloud2>(
"trajectory_cloud", 1);
170 std::vector<base_local_planner::TrajectoryCostFunction*> critics;
180 std::vector<base_local_planner::TrajectorySampleGenerator*> generator_list;
189 bool DWAPlanner::getCellCosts(
int cx,
int cy,
float &path_cost,
float &goal_cost,
float &occ_cost,
float &total_cost) {
207 bool DWAPlanner::setPlan(
const std::vector<geometry_msgs::PoseStamped>& orig_global_plan) {
219 Eigen::Vector3f vel_samples){
222 geometry_msgs::PoseStamped goal_pose =
global_plan_.back();
223 Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y,
tf2::getYaw(goal_pose.pose.orientation));
236 ROS_WARN(
"Invalid Trajectory %f, %f, %f, cost: %f", vel_samples[0], vel_samples[1], vel_samples[2], cost);
244 const geometry_msgs::PoseStamped& global_pose,
245 const std::vector<geometry_msgs::PoseStamped>& new_plan,
246 const std::vector<geometry_msgs::Point>& footprint_spec) {
248 for (
unsigned int i = 0; i < new_plan.size(); ++i) {
261 geometry_msgs::PoseStamped goal_pose =
global_plan_.back();
263 Eigen::Vector3f pos(global_pose.pose.position.x, global_pose.pose.position.y,
tf2::getYaw(global_pose.pose.orientation));
265 (pos[0] - goal_pose.pose.position.x) * (pos[0] - goal_pose.pose.position.x) +
266 (pos[1] - goal_pose.pose.position.y) * (pos[1] - goal_pose.pose.position.y);
273 std::vector<geometry_msgs::PoseStamped> front_global_plan =
global_plan_;
274 double angle_to_goal = atan2(goal_pose.pose.position.y - pos[1], goal_pose.pose.position.x - pos[0]);
275 front_global_plan.back().pose.position.x = front_global_plan.back().pose.position.x +
277 front_global_plan.back().pose.position.y = front_global_plan.back().pose.position.y +
forward_point_distance_ *
298 const geometry_msgs::PoseStamped& global_pose,
299 const geometry_msgs::PoseStamped& global_vel,
300 geometry_msgs::PoseStamped& drive_velocities) {
305 Eigen::Vector3f pos(global_pose.pose.position.x, global_pose.pose.position.y,
tf2::getYaw(global_pose.pose.orientation));
306 Eigen::Vector3f vel(global_vel.pose.position.x, global_vel.pose.position.y,
tf2::getYaw(global_vel.pose.orientation));
307 geometry_msgs::PoseStamped goal_pose =
global_plan_.back();
308 Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y,
tf2::getYaw(goal_pose.pose.orientation));
320 std::vector<base_local_planner::Trajectory> all_explored;
325 sensor_msgs::PointCloud2 traj_cloud;
330 cloud_mod.setPointCloud2Fields(5,
"x", 1, sensor_msgs::PointField::FLOAT32,
331 "y", 1, sensor_msgs::PointField::FLOAT32,
332 "z", 1, sensor_msgs::PointField::FLOAT32,
333 "theta", 1, sensor_msgs::PointField::FLOAT32,
334 "cost", 1, sensor_msgs::PointField::FLOAT32);
336 unsigned int num_points = 0;
337 for(std::vector<base_local_planner::Trajectory>::iterator t=all_explored.begin(); t != all_explored.end(); ++t)
341 num_points +=
t->getPointsSize();
344 cloud_mod.resize(num_points);
346 for(std::vector<base_local_planner::Trajectory>::iterator t=all_explored.begin(); t != all_explored.end(); ++t)
351 for(
unsigned int i = 0; i <
t->getPointsSize(); ++i) {
352 double p_x, p_y, p_th;
353 t->getPoint(i, p_x, p_y, p_th);
358 iter_x[4] =
t->cost_;
376 drive_velocities.pose.position.x = 0;
377 drive_velocities.pose.position.y = 0;
378 drive_velocities.pose.position.z = 0;
379 drive_velocities.pose.orientation.w = 1;
380 drive_velocities.pose.orientation.x = 0;
381 drive_velocities.pose.orientation.y = 0;
382 drive_velocities.pose.orientation.z = 0;
386 drive_velocities.pose.position.z = 0;