backwards_compatibility.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, Locus Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 #include <dwb_local_planner/backwards_compatibility.h>
00035 #include <nav_2d_utils/parameters.h>
00036 #include <string>
00037 #include <vector>
00038 
00039 namespace dwb_local_planner
00040 {
00041 
00042 using nav_2d_utils::moveParameter;
00043 
00044 std::string getBackwardsCompatibleDefaultGenerator(const ros::NodeHandle& nh)
00045 {
00046   bool use_dwa;
00047   nh.param("use_dwa", use_dwa, true);
00048   if (use_dwa)
00049   {
00050     return "dwb_plugins::LimitedAccelGenerator";
00051   }
00052   else
00053   {
00054     return "dwb_plugins::StandardTrajectoryGenerator";
00055   }
00056 }
00057 
00058 void loadBackwardsCompatibleParameters(const ros::NodeHandle& nh)
00059 {
00060   std::vector<std::string> critic_names;
00061   ROS_INFO_NAMED("DWBLocalPlanner", "No critics configured! Using the default set.");
00062   critic_names.push_back("RotateToGoal");       // discards trajectories that move forward when already at goal
00063   critic_names.push_back("Oscillation");        // discards oscillating motions (assisgns cost -1)
00064   critic_names.push_back("ObstacleFootprint");  // discards trajectories that move into obstacles
00065   critic_names.push_back("GoalAlign");          // prefers trajectories that make the nose go towards (local) nose goal
00066   critic_names.push_back("PathAlign");          // prefers trajectories that keep the robot nose on nose path
00067   critic_names.push_back("PathDist");           // prefers trajectories on global path
00068   critic_names.push_back("GoalDist");           // prefers trajectories that go towards (local) goal,
00069                                                 //         based on wave propagation
00070   nh.setParam("critics", critic_names);
00071   moveParameter(nh, "path_distance_bias", "PathAlign/scale", 32.0, false);
00072   moveParameter(nh, "goal_distance_bias", "GoalAlign/scale", 24.0, false);
00073   moveParameter(nh, "path_distance_bias", "PathDist/scale", 32.0);
00074   moveParameter(nh, "goal_distance_bias", "GoalDist/scale", 24.0);
00075   moveParameter(nh, "occdist_scale",      "ObstacleFootprint/scale", 0.01);
00076 
00077   moveParameter(nh, "max_scaling_factor", "ObstacleFootprint/max_scaling_factor", 0.2);
00078   moveParameter(nh, "scaling_speed",      "ObstacleFootprint/scaling_speed", 0.25);
00079 }
00080 
00081 }  // namespace dwb_local_planner


dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Wed Jun 26 2019 20:09:38