Compare commits

...

11 Commits

Author SHA1 Message Date
邱棚 416edce6c4 doc:add comment 2024-07-15 16:05:48 +08:00
amakarow 5b4e465fec
Merge pull request #24 from matijazigic/mzigic/reconfigure_fix
Prevent reconfigure from overwriting parameters at the initialization
2021-01-04 17:59:34 +01:00
Matija fc983b69ef Prevent reconfigure from overwriting params at the initialization 2020-12-13 14:52:26 +01:00
amakarow 9700f11f70
Merge pull request #21 from johuber/patch-1
Fix libraries of catkin_package mpc_local_planner
2020-11-08 19:39:14 +01:00
Jonathan Huber eb9b936f01
Fix libraries of catkin_package mpc_local_planner 2020-10-27 16:57:01 +01:00
amakarow f5c5496be7
Merge pull request #20 from johuber/patch-1
[examples] Add missing global_planner dependency
2020-10-25 17:51:15 +01:00
amakarow 225285e387
Merge pull request #19 from johuber/patch-2
Remove faulty generate_messages dependency
2020-10-25 17:50:37 +01:00
Jonathan Huber adf6472628
[examples] Add missing global_planner dependency 2020-10-22 13:15:11 +02:00
Jonathan Huber 487ce16e59
Remove faulty generate_messages dependency 2020-10-20 11:02:58 +02:00
amakarow bbc10df055
Merge pull request #18 from kosmastsk/melodic-devel
Add dynamic reconfigure
2020-10-17 17:16:36 +02:00
kosmastsk ae89b1966b Add dynamic reconfigure 2020-08-12 20:35:34 +03:00
7 changed files with 216 additions and 52 deletions

View File

@ -132,11 +132,13 @@ set(EXTERNAL_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR})
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
#add dynamic reconfigure api
#find_package(catkin REQUIRED dynamic_reconfigure)
generate_dynamic_reconfigure_options(
cfg/mpc_collision.cfg
cfg/mpc_controller.cfg
cfg/mpc_footprint.cfg
)
###################################
## catkin specific configuration ##
@ -149,8 +151,8 @@ set(EXTERNAL_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR})
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include ${EXTERNAL_INCLUDE_DIRS}
LIBRARIES mpc_local_planner_numerics mpc_local_planner_optimization
CATKIN_DEPENDS roscpp mpc_local_planner_msgs control_box_rst teb_local_planner
LIBRARIES mpc_local_planner_utils mpc_local_planner_optimal_control mpc_local_planner
CATKIN_DEPENDS roscpp mpc_local_planner_msgs control_box_rst teb_local_planner dynamic_reconfigure
# DEPENDS
)
@ -188,6 +190,9 @@ add_library(mpc_local_planner
src/mpc_local_planner_ros.cpp
)
# Dynamic reconfigure: make sure configure headers are built before any node using them
add_dependencies(mpc_local_planner ${PROJECT_NAME}_gencfg)
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide

View File

@ -0,0 +1,28 @@
#!/usr/bin/env python
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
# This unusual line allows to reuse existing parameter definitions
# that concern all localplanners
#add_generic_localplanner_params(gen)
# For integers and doubles:
# Name Type Reconfiguration level
# Description
# Default Min Max
# Collision avoidance
grp_collision = gen.add_group("Collision avoidance", type="tab")
grp_collision.add("include_costmap_obstacles", bool_t, 0, "Specify whether the obstacles in the costmap should be taken into account directly (this is necessary if no seperate clustering and detection is implemented)", True)
grp_collision.add("costmap_obstacles_behind_robot_dist", double_t, 0, "Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify distance in meters)", 1.5, 0, 10)
grp_collision.add("collision_check_min_resolution_angular", double_t, 0, "", 3.1415, -3.1415, 3.1415)
grp_collision.add("collision_check_no_poses", int_t, 0, "", -1, -1, 100)
exit(gen.generate("mpc_local_planner", "mpc_local_planner", "CollisionReconfigure"))

View File

@ -0,0 +1,33 @@
#!/usr/bin/env python
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
# This unusual line allows to reuse existing parameter definitions
# that concern all localplanners
#add_generic_localplanner_params(gen)
# For integers and doubles:
# Name Type Reconfiguration level
# Description
# Default Min Max
grp_controller = gen.add_group("Controller", type="tab")
# Controller
grp_controller.add("xy_goal_tolerance", double_t, 0, "Allowed final euclidean distance to the goal position", 0.2, 0, 1)
grp_controller.add("yaw_goal_tolerance", double_t, 0, "Allowed final orientation error to the goal orientation", 0.1, 0, 1)
grp_controller.add("global_plan_overwrite_orientation", bool_t, 0, "Some global planners are not considering the orientation at local subgoals between start and global goal, therefore determine it automatically", True)
grp_controller.add("global_plan_prune_distance", double_t, 0, "", 1.0, 0, 10)
grp_controller.add("max_global_plan_lookahead_dist", double_t, 0, "Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into account for optimization [if 0 or negative: disabled; the length is also bounded by the local costmap size]", 1.5, 0, 10)
grp_controller.add("global_plan_viapoint_sep", double_t, 0, "Min. separation between each two consecutive via-points extracted from the global plan [if negative: disabled]", -1, -1, 10)
exit(gen.generate("mpc_local_planner", "mpc_local_planner", "ControllerReconfigure"))

View File

@ -0,0 +1,22 @@
#!/usr/bin/env python
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
# This unusual line allows to reuse existing parameter definitions
# that concern all localplanners
#add_generic_localplanner_params(gen)
# For integers and doubles:
# Name Type Reconfiguration level
# Description
# Default Min Max
# Footprint model
grp_footprint = gen.add_group("Footprint", type="tab")
grp_footprint.add("is_footprint_dynamic", bool_t, 0, "If true, updated the footprint before checking trajectory feasibility", False)
exit(gen.generate("mpc_local_planner", "mpc_local_planner", "FootprintReconfigure"))

View File

@ -58,8 +58,10 @@
#include <costmap_converter/costmap_converter_interface.h>
// dynamic reconfigure
// #include <dynamic_reconfigure/server.h>
// #include <mpc_local_planner/MpcLocalPlannerReconfigureConfig.h>
#include <dynamic_reconfigure/server.h>
#include <mpc_local_planner/ControllerReconfigureConfig.h>
#include <mpc_local_planner/CollisionReconfigureConfig.h>
#include <mpc_local_planner/FootprintReconfigureConfig.h>
#include <boost/shared_ptr.hpp>
@ -221,6 +223,11 @@ class MpcLocalPlannerROS : public nav_core::BaseLocalPlanner, public mbf_costmap
*/
static double getNumberFromXMLRPC(XmlRpc::XmlRpcValue& value, const std::string& full_param_name);
/**
* @brief Return the internal config mutex
*/
boost::mutex& configMutex() { return config_mutex_; }
//@}
protected:
@ -258,13 +265,31 @@ class MpcLocalPlannerROS : public nav_core::BaseLocalPlanner, public mbf_costmap
void updateViaPointsContainer(const std::vector<geometry_msgs::PoseStamped>& transformed_plan, double min_separation);
/**
* @brief Callback for the dynamic_reconfigure node.
* @brief Callback for the dynamic_reconfigure controller node.
*
* This callback allows to modify parameters dynamically at runtime without restarting the node
* @param config Reference to the dynamic reconfigure config
* @param level Dynamic reconfigure level
*/
// void reconfigureCB(MpcLocalPlannerReconfigureConfig& config, uint32_t level);
void reconfigureControllerCB(ControllerReconfigureConfig& config, uint32_t level);
/**
* @brief Callback for the dynamic_reconfigure collision node.
*
* This callback allows to modify parameters dynamically at runtime without restarting the node
* @param config Reference to the dynamic reconfigure config
* @param level Dynamic reconfigure level
*/
void reconfigureCollisionCB(CollisionReconfigureConfig& config, uint32_t level);
/**
* @brief Callback for the dynamic_reconfigure footprint collision node.
*
* This callback allows to modify parameters dynamically at runtime without restarting the node
* @param config Reference to the dynamic reconfigure config
* @param level Dynamic reconfigure level
*/
void reconfigureFootprintCB(FootprintReconfigureConfig& config, uint32_t level);
/**
* @brief Callback for custom obstacles that are not obtained from the costmap
@ -373,8 +398,12 @@ class MpcLocalPlannerROS : public nav_core::BaseLocalPlanner, public mbf_costmap
pluginlib::ClassLoader<costmap_converter::BaseCostmapToPolygons> _costmap_converter_loader; //!< Load costmap converter plugins at runtime
boost::shared_ptr<costmap_converter::BaseCostmapToPolygons> _costmap_converter; //!< Store the current costmap_converter
// std::shared_ptr<dynamic_reconfigure::Server<MpcLocalPlannerReconfigureConfig>>
// dynamic_recfg_; //!< Dynamic reconfigure server to allow config modifications at runtime
boost::shared_ptr<dynamic_reconfigure::Server<ControllerReconfigureConfig>>
dynamic_controller_recfg_; //!< Dynamic reconfigure server to allow config modifications at runtime
boost::shared_ptr<dynamic_reconfigure::Server<CollisionReconfigureConfig>>
dynamic_collision_recfg_; //!< Dynamic reconfigure server to allow config modifications at runtime
boost::shared_ptr<dynamic_reconfigure::Server<FootprintReconfigureConfig>>
dynamic_footprint_recfg_; //!< Dynamic reconfigure server to allow config modifications at runtime
ros::Subscriber _custom_obst_sub; //!< Subscriber for custom obstacles received via a ObstacleMsg.
std::mutex _custom_obst_mutex; //!< Mutex that locks the obstacle array (multi-threaded)
costmap_converter::ObstacleArrayMsg _custom_obstacle_msg; //!< Copy of the most recent obstacle message
@ -423,6 +452,8 @@ class MpcLocalPlannerROS : public nav_core::BaseLocalPlanner, public mbf_costmap
} _params;
boost::mutex config_mutex_; //!< Mutex for config accesses and changes
struct CostmapConverterPlugin
{
std::string costmap_converter_plugin;

View File

@ -46,7 +46,9 @@ MpcLocalPlannerROS::MpcLocalPlannerROS()
_tf(nullptr),
_costmap_model(nullptr),
_costmap_converter_loader("costmap_converter", "costmap_converter::BaseCostmapToPolygons"),
/*dynamic_recfg_(NULL),*/
dynamic_controller_recfg_(NULL),
dynamic_collision_recfg_(NULL),
dynamic_footprint_recfg_(NULL),
_goal_reached(false),
_no_infeasible_plans(0),
/*last_preferred_rotdir_(RotType::none),*/
@ -56,22 +58,44 @@ MpcLocalPlannerROS::MpcLocalPlannerROS()
MpcLocalPlannerROS::~MpcLocalPlannerROS() {}
/*
void MpcLocalPlannerROS::reconfigureCB(TebLocalPlannerReconfigureConfig& config, uint32_t level)
void MpcLocalPlannerROS::reconfigureControllerCB(ControllerReconfigureConfig& config, uint32_t level)
{
cfg_.reconfigure(config);
boost::mutex::scoped_lock l(config_mutex_);
_params.xy_goal_tolerance = config.xy_goal_tolerance;
_params.yaw_goal_tolerance = config.yaw_goal_tolerance;
_params.global_plan_overwrite_orientation = config.global_plan_overwrite_orientation;
_params.global_plan_prune_distance = config.global_plan_prune_distance;
_params.max_global_plan_lookahead_dist = config.max_global_plan_lookahead_dist;
_params.global_plan_viapoint_sep = config.global_plan_viapoint_sep;
}
void MpcLocalPlannerROS::reconfigureFootprintCB(FootprintReconfigureConfig& config, uint32_t level)
{
boost::mutex::scoped_lock l(config_mutex_);
_params.is_footprint_dynamic = config.is_footprint_dynamic;
}
void MpcLocalPlannerROS::reconfigureCollisionCB(CollisionReconfigureConfig& config, uint32_t level)
{
boost::mutex::scoped_lock l(config_mutex_);
_params.include_costmap_obstacles = config.include_costmap_obstacles;
_params.costmap_obstacles_behind_robot_dist = config.costmap_obstacles_behind_robot_dist;
_params.collision_check_min_resolution_angular = config.collision_check_min_resolution_angular;
_params.collision_check_no_poses = config.collision_check_no_poses;
}
*/
void MpcLocalPlannerROS::initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros)
{
// check if the plugin is already initialized
// 检查插件是否已经初始化
if (!_initialized)
{
// create Node Handle with name of plugin (as used in move_base for loading)
// 创建一个Node Handle使用插件的名称如在move_base中加载
ros::NodeHandle nh("~/" + name);
// load plugin related main parameters
// 加载插件相关的主要参数
nh.param("controller/xy_goal_tolerance", _params.xy_goal_tolerance, _params.xy_goal_tolerance);
nh.param("controller/yaw_goal_tolerance", _params.yaw_goal_tolerance, _params.yaw_goal_tolerance);
nh.param("controller/global_plan_overwrite_orientation", _params.global_plan_overwrite_orientation,
@ -81,9 +105,11 @@ void MpcLocalPlannerROS::initialize(std::string name, tf2_ros::Buffer* tf, costm
nh.param("controller/global_plan_viapoint_sep", _params.global_plan_viapoint_sep, _params.global_plan_viapoint_sep);
_controller.setInitialPlanEstimateOrientation(_params.global_plan_overwrite_orientation);
// special parameters
// 特殊参数
nh.param("odom_topic", _params.odom_topic, _params.odom_topic);
nh.param("footprint_model/is_footprint_dynamic", _params.is_footprint_dynamic, _params.is_footprint_dynamic);
nh.param("collision_avoidance/include_costmap_obstacles", _params.include_costmap_obstacles, _params.include_costmap_obstacles);
nh.param("collision_avoidance/costmap_obstacles_behind_robot_dist", _params.costmap_obstacles_behind_robot_dist,
_params.costmap_obstacles_behind_robot_dist);
@ -92,46 +118,46 @@ void MpcLocalPlannerROS::initialize(std::string name, tf2_ros::Buffer* tf, costm
nh.param("collision_avoidance/collision_check_min_resolution_angular", _params.collision_check_min_resolution_angular,
_params.collision_check_min_resolution_angular);
// costmap converter plugin related parameters
// 代价地图转换器插件相关参数
nh.param("costmap_converter_plugin", _costmap_conv_params.costmap_converter_plugin, _costmap_conv_params.costmap_converter_plugin);
nh.param("costmap_converter_rate", _costmap_conv_params.costmap_converter_rate, _costmap_conv_params.costmap_converter_rate);
nh.param("costmap_converter_spin_thread", _costmap_conv_params.costmap_converter_spin_thread,
_costmap_conv_params.costmap_converter_spin_thread);
// reserve some memory for obstacles
// 预留一些内存用于障碍物
_obstacles.reserve(700);
// init other variables
// 初始化其他变量
_tf = tf;
_costmap_ros = costmap_ros;
_costmap = _costmap_ros->getCostmap(); // locking should be done in MoveBase.
_costmap = _costmap_ros->getCostmap(); // 应在MoveBase中进行锁定
_costmap_model = std::make_shared<base_local_planner::CostmapModel>(*_costmap);
_global_frame = _costmap_ros->getGlobalFrameID();
_robot_base_frame = _costmap_ros->getBaseFrameID();
// create robot footprint/contour model for optimization
// 创建用于优化的机器人足迹/轮廓模型
_robot_model = getRobotFootprintFromParamServer(nh, _costmap_ros);
// create the planner instance
// 创建规划器实例
if (!_controller.configure(nh, _obstacles, _robot_model, _via_points))
{
ROS_ERROR("Controller configuration failed.");
return;
}
// create visualization instance
// 创建规划器实例
_publisher.initialize(nh, _controller.getRobotDynamics(), _global_frame);
// Initialize a costmap to polygon converter
// 初始化代价地图到多边形的转换器
if (!_costmap_conv_params.costmap_converter_plugin.empty())
{
try
{
_costmap_converter = _costmap_converter_loader.createInstance(_costmap_conv_params.costmap_converter_plugin);
std::string converter_name = _costmap_converter_loader.getName(_costmap_conv_params.costmap_converter_plugin);
// replace '::' by '/' to convert the c++ namespace to a NodeHandle namespace
// 将'::'替换为'/'以将C++命名空间转换为NodeHandle命名空间
boost::replace_all(converter_name, "::", "/");
_costmap_converter->setOdomTopic(_params.odom_topic);
_costmap_converter->initialize(ros::NodeHandle(nh, "costmap_converter/" + converter_name));
@ -153,35 +179,46 @@ void MpcLocalPlannerROS::initialize(std::string name, tf2_ros::Buffer* tf, costm
else
ROS_INFO("No costmap conversion plugin specified. All occupied costmap cells are treaten as point obstacles.");
// Get footprint of the robot and minimum and maximum distance from the center of the robot to its footprint vertices.
// 获取机器人的足迹,以及从机器人中心到其足迹顶点的最小和最大距离
_footprint_spec = _costmap_ros->getRobotFootprint();
costmap_2d::calculateMinAndMaxDistances(_footprint_spec, _robot_inscribed_radius, _robot_circumscribed_radius);
// init the odom helper to receive the robot's velocity from odom messages
// 初始化里程计助手以从里程计消息中接收机器人的速度
_odom_helper.setOdomTopic(_params.odom_topic);
// setup dynamic reconfigure
/*
dynamic_recfg_ = boost::make_shared<dynamic_reconfigure::Server<MpcLocalPlannerReconfigureConfig>>(nh);
dynamic_reconfigure::Server<MpcLocalPlannerReconfigureConfig>::CallbackType cb =
boost::bind(&MpcLocalPlanner::reconfigureCB, this, _1, _2);
dynamic_recfg_->setCallback(cb);
*/
// 设置动态重配置
ros::NodeHandle controller_nh(nh, "controller");
dynamic_controller_recfg_ = boost::make_shared<dynamic_reconfigure::Server<ControllerReconfigureConfig>>(controller_nh);
dynamic_reconfigure::Server<ControllerReconfigureConfig>::CallbackType controller_cb =
boost::bind(&MpcLocalPlannerROS::reconfigureControllerCB, this, _1, _2);
dynamic_controller_recfg_->setCallback(controller_cb);
// validate optimization footprint and costmap footprint
ros::NodeHandle collision_nh(nh, "collision");
dynamic_collision_recfg_ = boost::make_shared<dynamic_reconfigure::Server<CollisionReconfigureConfig>>(collision_nh);
dynamic_reconfigure::Server<CollisionReconfigureConfig>::CallbackType collision_cb =
boost::bind(&MpcLocalPlannerROS::reconfigureCollisionCB, this, _1, _2);
dynamic_collision_recfg_->setCallback(collision_cb);
ros::NodeHandle footprint_nh(nh, "footprint_model");
dynamic_footprint_recfg_ = boost::make_shared<dynamic_reconfigure::Server<FootprintReconfigureConfig>>(footprint_nh);
dynamic_reconfigure::Server<FootprintReconfigureConfig>::CallbackType footprint_cb =
boost::bind(&MpcLocalPlannerROS::reconfigureFootprintCB, this, _1, _2);
dynamic_footprint_recfg_->setCallback(footprint_cb);
// 验证优化足迹和代价地图足迹
validateFootprints(_robot_model->getInscribedRadius(), _robot_inscribed_radius, _controller.getInequalityConstraint()->getMinimumDistance());
// setup callback for custom obstacles
// 设置自定义障碍物的回调函数
_custom_obst_sub = nh.subscribe("obstacles", 1, &MpcLocalPlannerROS::customObstacleCB, this);
// setup callback for custom via-points
// 设置自定义路径点的回调函数
_via_points_sub = nh.subscribe("via_points", 1, &MpcLocalPlannerROS::customViaPointsCB, this);
// additional move base params
// 其他move_base参数
ros::NodeHandle nh_move_base("~");
nh_move_base.param("controller_frequency", _params.controller_frequency, _params.controller_frequency);
// set initialized flag
// 设置已初始化标志
_initialized = true;
ROS_DEBUG("mpc_local_planner plugin initialized.");
@ -192,23 +229,31 @@ void MpcLocalPlannerROS::initialize(std::string name, tf2_ros::Buffer* tf, costm
}
}
/**
* @brief
*
*
*
* @param orig_global_plan 姿
* @return bool truefalse
*/
bool MpcLocalPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan)
{
// check if plugin is initialized
// 检查插件是否已初始化
if (!_initialized)
{
ROS_ERROR("mpc_local_planner has not been initialized, please call initialize() before using this planner");
return false;
}
// store the global plan
// 存储全局路径计划
_global_plan.clear();
_global_plan = orig_global_plan;
// we do not clear the local planner here, since setPlan is called frequently whenever the global planner updates the plan.
// the local planner checks whether it is required to reinitialize the trajectory or not within each velocity computation step.
// 这里不清除局部规划器因为每当全局规划器更新计划时setPlan 会被频繁调用。
// 局部规划器在每次速度计算步骤中检查是否需要重新初始化轨迹。
// reset goal_reached_ flag
// 重置目标到达标志
_goal_reached = false;
return true;
@ -332,8 +377,7 @@ uint32_t MpcLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseSt
// updateControlFromTwist()
// Do not allow config changes during the following optimization step
// TODO(roesmann): we need something similar in case we allow dynamic reconfiguration:
// boost::mutex::scoped_lock cfg_lock(cfg_.configMutex());
boost::mutex::scoped_lock cfg_lock(configMutex());
// Now perform the actual planning
// bool success = planner_->plan(transformed_plan, &robot_vel_, cfg_.goal_tolerance.free_goal_vel);

View File

@ -20,6 +20,7 @@
<exec_depend>move_base</exec_depend>
<exec_depend>map_server</exec_depend>
<exec_depend>amcl</exec_depend>
<exec_depend>global_planner</exec_depend>
<!-- The export tag contains other, unspecified, tags -->