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;
122 goal_costs_(planner_util->getCostmap(), 0.0, 0.0, true),
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 private_nh.
param(
"global_frame_id",
frame_id_, std::string(
"odom"));
166 std::vector<base_local_planner::TrajectoryCostFunction*> critics;
176 std::vector<base_local_planner::TrajectorySampleGenerator*> generator_list;
215 Eigen::Vector3f vel_samples){
218 geometry_msgs::PoseStamped goal_pose =
global_plan_.back();
219 Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y,
tf2::getYaw(goal_pose.pose.orientation));
232 ROS_WARN(
"Invalid Trajectory %f, %f, %f, cost: %f", vel_samples[0], vel_samples[1], vel_samples[2], cost);
240 const geometry_msgs::PoseStamped& global_pose,
241 const std::vector<geometry_msgs::PoseStamped>& new_plan,
242 const std::vector<geometry_msgs::Point>& footprint_spec) {
244 for (
unsigned int i = 0; i < new_plan.size(); ++i) {
257 geometry_msgs::PoseStamped goal_pose =
global_plan_.back();
259 Eigen::Vector3f pos(global_pose.pose.position.x, global_pose.pose.position.y,
tf2::getYaw(global_pose.pose.orientation));
261 (pos[0] - goal_pose.pose.position.x) * (pos[0] - goal_pose.pose.position.x) +
262 (pos[1] - goal_pose.pose.position.y) * (pos[1] - goal_pose.pose.position.y);
269 std::vector<geometry_msgs::PoseStamped> front_global_plan =
global_plan_;
270 double angle_to_goal =
atan2(goal_pose.pose.position.y - pos[1], goal_pose.pose.position.x - pos[0]);
271 front_global_plan.back().pose.position.x = front_global_plan.back().pose.position.x +
273 front_global_plan.back().pose.position.y = front_global_plan.back().pose.position.y +
forward_point_distance_ *
294 const geometry_msgs::PoseStamped& global_pose,
295 const geometry_msgs::PoseStamped& global_vel,
296 geometry_msgs::PoseStamped& drive_velocities) {
301 Eigen::Vector3f pos(global_pose.pose.position.x, global_pose.pose.position.y,
tf2::getYaw(global_pose.pose.orientation));
302 Eigen::Vector3f vel(global_vel.pose.position.x, global_vel.pose.position.y,
tf2::getYaw(global_vel.pose.orientation));
303 geometry_msgs::PoseStamped goal_pose =
global_plan_.back();
304 Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y,
tf2::getYaw(goal_pose.pose.orientation));
316 std::vector<base_local_planner::Trajectory> all_explored;
321 sensor_msgs::PointCloud2 traj_cloud;
327 "y", 1, sensor_msgs::PointField::FLOAT32,
328 "z", 1, sensor_msgs::PointField::FLOAT32,
329 "theta", 1, sensor_msgs::PointField::FLOAT32,
330 "cost", 1, sensor_msgs::PointField::FLOAT32);
332 unsigned int num_points = 0;
333 for(std::vector<base_local_planner::Trajectory>::iterator
t=all_explored.begin();
t != all_explored.end(); ++
t)
337 num_points +=
t->getPointsSize();
340 cloud_mod.
resize(num_points);
342 for(std::vector<base_local_planner::Trajectory>::iterator
t=all_explored.begin();
t != all_explored.end(); ++
t)
347 for(
unsigned int i = 0; i <
t->getPointsSize(); ++i) {
348 double p_x, p_y, p_th;
349 t->getPoint(i, p_x, p_y, p_th);
354 iter_x[4] =
t->cost_;
372 drive_velocities.pose.position.x = 0;
373 drive_velocities.pose.position.y = 0;
374 drive_velocities.pose.position.z = 0;
375 drive_velocities.pose.orientation.w = 1;
376 drive_velocities.pose.orientation.x = 0;
377 drive_velocities.pose.orientation.y = 0;
378 drive_velocities.pose.orientation.z = 0;
382 drive_velocities.pose.position.z = 0;
void initialise(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, const Eigen::Vector3f &goal, base_local_planner::LocalPlannerLimits *limits, const Eigen::Vector3f &vsamples, std::vector< Eigen::Vector3f > additional_samples, bool discretize_by_time=false)
void setFootprint(std::vector< geometry_msgs::Point > footprint_spec)
void reconfigure(DWAPlannerConfig &cfg)
Reconfigures the trajectory planner.
std::string getGlobalFrame()
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
bool generateTrajectory(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f sample_target_vel, base_local_planner::Trajectory &traj)
base_local_planner::MapGridCostFunction goal_front_costs_
void publishCostCloud(const costmap_2d::Costmap2D *costmap_p_)
base_local_planner::MapGridCostFunction goal_costs_
double sim_period_
The number of seconds to use to compute max/min vels for dwa.
costmap_2d::Costmap2D * getCostmap()
void resetOscillationFlags()
base_local_planner::OscillationCostFunction oscillation_costs_
double goal_distance_bias_
base_local_planner::LocalPlannerUtil * planner_util_
bool publish_cost_grid_pc_
Whether or not to build and publish a PointCloud.
void setPointCloud2Fields(int n_fields,...)
double unreachableCellCosts()
bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)
Compute the components and total cost for a map grid cell.
void initialize(const std::string &name, std::string frame, boost::function< bool(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)> cost_function)
base_local_planner::TwirlingCostFunction twirling_costs_
geometry_msgs::TransformStamped t
std::vector< geometry_msgs::PoseStamped > global_plan_
double scoreTrajectory(Trajectory &traj, double best_traj_cost)
void setStopOnFailure(bool stop_on_failure)
base_local_planner::MapGridCostFunction alignment_costs_
DWAPlanner(std::string name, base_local_planner::LocalPlannerUtil *planner_util)
Constructor for the planner.
void setSumScores(bool score_sums)
boost::mutex configuration_mutex_
base_local_planner::SimpleScoredSamplingPlanner scored_sampling_planner_
bool findBestTrajectory(Trajectory &traj, std::vector< Trajectory > *all_explored=0)
Eigen::Vector3f vsamples_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
ros::Publisher traj_cloud_pub_
base_local_planner::ObstacleCostFunction obstacle_costs_
base_local_planner::MapGridVisualizer map_viz_
The map grid visualizer for outputting the potential field generated by the cost function.
LocalPlannerLimits getCurrentLimits()
base_local_planner::MapGridCostFunction path_costs_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void setParameters(double sim_time, double sim_granularity, double angular_sim_granularity, bool use_dwa=false, double sim_period=0.0)
double getYaw(const A &a)
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
bool searchParam(const std::string &key, std::string &result) const
double path_distance_bias_
double forward_point_distance_
void setParams(double max_trans_vel, double max_scaling_factor, double scaling_speed)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
void setTargetPoses(std::vector< geometry_msgs::PoseStamped > target_poses)
base_local_planner::Trajectory result_traj_
base_local_planner::SimpleTrajectoryGenerator generator_
void convert(const A &a, B &b)
double getResolution() const
double stop_time_buffer_
How long before hitting something we're going to enforce that the robot stop.
double getCellCosts(unsigned int cx, unsigned int cy)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
void updatePlanAndLocalCosts(const geometry_msgs::PoseStamped &global_pose, const std::vector< geometry_msgs::PoseStamped > &new_plan, const std::vector< geometry_msgs::Point > &footprint_spec)
Update the cost functions before planning.
void setScale(double scale)
void setXShift(double xshift)
base_local_planner::Trajectory findBestPath(const geometry_msgs::PoseStamped &global_pose, const geometry_msgs::PoseStamped &global_vel, geometry_msgs::PoseStamped &drive_velocities)
Given the current position and velocity of the robot, find the best trajectory to exectue...
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
unsigned char getCost(unsigned int mx, unsigned int my) const
void updateOscillationFlags(Eigen::Vector3f pos, base_local_planner::Trajectory *traj, double min_vel_trans)
void setOscillationResetDist(double dist, double angle)
bool checkTrajectory(const Eigen::Vector3f pos, const Eigen::Vector3f vel, const Eigen::Vector3f vel_samples)
Check if a trajectory is legal for a position/velocity pair.