Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include "mbf_costmap_nav/costmap_controller_execution.h"
00041
00042 namespace mbf_costmap_nav
00043 {
00044
00045 CostmapControllerExecution::CostmapControllerExecution(
00046 const std::string name,
00047 const mbf_costmap_core::CostmapController::Ptr &controller_ptr,
00048 const ros::Publisher& vel_pub,
00049 const ros::Publisher& goal_pub,
00050 const TFPtr &tf_listener_ptr,
00051 CostmapPtr &costmap_ptr,
00052 const MoveBaseFlexConfig &config,
00053 boost::function<void()> setup_fn,
00054 boost::function<void()> cleanup_fn)
00055 : AbstractControllerExecution(name, controller_ptr, vel_pub, goal_pub, tf_listener_ptr,
00056 toAbstract(config), setup_fn, cleanup_fn),
00057 costmap_ptr_(costmap_ptr)
00058 {
00059 ros::NodeHandle private_nh("~");
00060 private_nh.param("controller_lock_costmap", lock_costmap_, true);
00061 }
00062
00063 CostmapControllerExecution::~CostmapControllerExecution()
00064 {
00065 }
00066
00067 mbf_abstract_nav::MoveBaseFlexConfig CostmapControllerExecution::toAbstract(const MoveBaseFlexConfig &config)
00068 {
00069
00070 mbf_abstract_nav::MoveBaseFlexConfig abstract_config;
00071 abstract_config.controller_frequency = config.controller_frequency;
00072 abstract_config.controller_patience = config.controller_patience;
00073 abstract_config.controller_max_retries = config.controller_max_retries;
00074 abstract_config.oscillation_timeout = config.oscillation_timeout;
00075 abstract_config.oscillation_distance = config.oscillation_distance;
00076 return abstract_config;
00077 }
00078
00079 uint32_t CostmapControllerExecution::computeVelocityCmd(
00080 const geometry_msgs::PoseStamped& robot_pose,
00081 const geometry_msgs::TwistStamped& robot_velocity,
00082 geometry_msgs::TwistStamped& vel_cmd,
00083 std::string& message)
00084 {
00085
00086 if (lock_costmap_)
00087 {
00088 boost::lock_guard<costmap_2d::Costmap2D::mutex_t> lock(*(costmap_ptr_->getCostmap()->getMutex()));
00089 return controller_->computeVelocityCommands(robot_pose, robot_velocity, vel_cmd, message);
00090 }
00091 return controller_->computeVelocityCommands(robot_pose, robot_velocity, vel_cmd, message);
00092 }
00093
00094 }