doc:add comment

master
邱棚 2024-07-15 16:32:05 +08:00
parent 416edce6c4
commit 3b8e1e5c73
1 changed files with 278 additions and 92 deletions

View File

@ -58,6 +58,14 @@ MpcLocalPlannerROS::MpcLocalPlannerROS()
MpcLocalPlannerROS::~MpcLocalPlannerROS() {} MpcLocalPlannerROS::~MpcLocalPlannerROS() {}
/**
* @brief
*
*
*
* @param config
* @param level
*/
void MpcLocalPlannerROS::reconfigureControllerCB(ControllerReconfigureConfig& config, uint32_t level) void MpcLocalPlannerROS::reconfigureControllerCB(ControllerReconfigureConfig& config, uint32_t level)
{ {
boost::mutex::scoped_lock l(config_mutex_); boost::mutex::scoped_lock l(config_mutex_);
@ -70,6 +78,14 @@ void MpcLocalPlannerROS::reconfigureControllerCB(ControllerReconfigureConfig& co
_params.global_plan_viapoint_sep = config.global_plan_viapoint_sep; _params.global_plan_viapoint_sep = config.global_plan_viapoint_sep;
} }
/**
* @brief
*
*
*
* @param config
* @param level
*/
void MpcLocalPlannerROS::reconfigureFootprintCB(FootprintReconfigureConfig& config, uint32_t level) void MpcLocalPlannerROS::reconfigureFootprintCB(FootprintReconfigureConfig& config, uint32_t level)
{ {
boost::mutex::scoped_lock l(config_mutex_); boost::mutex::scoped_lock l(config_mutex_);
@ -77,6 +93,14 @@ void MpcLocalPlannerROS::reconfigureFootprintCB(FootprintReconfigureConfig& conf
_params.is_footprint_dynamic = config.is_footprint_dynamic; _params.is_footprint_dynamic = config.is_footprint_dynamic;
} }
/**
* @brief
*
*
*
* @param config
* @param level
*/
void MpcLocalPlannerROS::reconfigureCollisionCB(CollisionReconfigureConfig& config, uint32_t level) void MpcLocalPlannerROS::reconfigureCollisionCB(CollisionReconfigureConfig& config, uint32_t level)
{ {
boost::mutex::scoped_lock l(config_mutex_); boost::mutex::scoped_lock l(config_mutex_);
@ -87,6 +111,15 @@ void MpcLocalPlannerROS::reconfigureCollisionCB(CollisionReconfigureConfig& conf
_params.collision_check_no_poses = config.collision_check_no_poses; _params.collision_check_no_poses = config.collision_check_no_poses;
} }
/**
* @brief
*
* MpcLocalPlannerROS
*
* @param name
* @param tf TF2
* @param costmap_ros costmap_2d::Costmap2DROS
*/
void MpcLocalPlannerROS::initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros) void MpcLocalPlannerROS::initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros)
{ {
// 检查插件是否已经初始化 // 检查插件是否已经初始化
@ -259,6 +292,14 @@ bool MpcLocalPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>&
return true; return true;
} }
/**
* @brief
*
*
*
* @param cmd_vel
* @return bool truefalse
*/
bool MpcLocalPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel) bool MpcLocalPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel)
{ {
std::string dummy_message; std::string dummy_message;
@ -268,11 +309,21 @@ bool MpcLocalPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel)
cmd_vel = cmd_vel_stamped.twist; cmd_vel = cmd_vel_stamped.twist;
return outcome == mbf_msgs::ExePathResult::SUCCESS; return outcome == mbf_msgs::ExePathResult::SUCCESS;
} }
/**
* @brief
*
*
*
* @param pose 姿
* @param velocity
* @param cmd_vel
* @param message
* @return uint32_t
*/
uint32_t MpcLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseStamped& pose, const geometry_msgs::TwistStamped& velocity, uint32_t MpcLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseStamped& pose, const geometry_msgs::TwistStamped& velocity,
geometry_msgs::TwistStamped& cmd_vel, std::string& message) geometry_msgs::TwistStamped& cmd_vel, std::string& message)
{ {
// check if plugin initialized // 检查插件是否已初始化
if (!_initialized) if (!_initialized)
{ {
ROS_ERROR("mpc_local_planner has not been initialized, please call initialize() before using this planner"); ROS_ERROR("mpc_local_planner has not been initialized, please call initialize() before using this planner");
@ -287,22 +338,22 @@ uint32_t MpcLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseSt
cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0; cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0;
_goal_reached = false; _goal_reached = false;
// Get robot pose // 获取机器人位姿
geometry_msgs::PoseStamped robot_pose; geometry_msgs::PoseStamped robot_pose;
_costmap_ros->getRobotPose(robot_pose); _costmap_ros->getRobotPose(robot_pose);
_robot_pose = PoseSE2(robot_pose.pose); _robot_pose = PoseSE2(robot_pose.pose);
// Get robot velocity // 获取机器人速度
geometry_msgs::PoseStamped robot_vel_tf; geometry_msgs::PoseStamped robot_vel_tf;
_odom_helper.getRobotVel(robot_vel_tf); _odom_helper.getRobotVel(robot_vel_tf);
_robot_vel.linear.x = robot_vel_tf.pose.position.x; _robot_vel.linear.x = robot_vel_tf.pose.position.x;
_robot_vel.linear.y = robot_vel_tf.pose.position.y; _robot_vel.linear.y = robot_vel_tf.pose.position.y;
_robot_vel.angular.z = tf2::getYaw(robot_vel_tf.pose.orientation); _robot_vel.angular.z = tf2::getYaw(robot_vel_tf.pose.orientation);
// prune global plan to cut off parts of the past (spatially before the robot) // 修剪全局计划,剪掉机器人之前的部分
pruneGlobalPlan(*_tf, robot_pose, _global_plan, _params.global_plan_prune_distance); pruneGlobalPlan(*_tf, robot_pose, _global_plan, _params.global_plan_prune_distance);
// Transform global plan to the frame of interest (w.r.t. the local costmap) // 修剪全局计划,剪掉机器人之前的部分
std::vector<geometry_msgs::PoseStamped> transformed_plan; std::vector<geometry_msgs::PoseStamped> transformed_plan;
int goal_idx; int goal_idx;
geometry_msgs::TransformStamped tf_plan_to_global; geometry_msgs::TransformStamped tf_plan_to_global;
@ -314,10 +365,10 @@ uint32_t MpcLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseSt
return mbf_msgs::ExePathResult::INTERNAL_ERROR; return mbf_msgs::ExePathResult::INTERNAL_ERROR;
} }
// update via-points container // 更新路径点容器
if (!_custom_via_points_active) updateViaPointsContainer(transformed_plan, _params.global_plan_viapoint_sep); if (!_custom_via_points_active) updateViaPointsContainer(transformed_plan, _params.global_plan_viapoint_sep);
// check if global goal is reached // 检查是否到达全局目标
geometry_msgs::PoseStamped global_goal; geometry_msgs::PoseStamped global_goal;
tf2::doTransform(_global_plan.back(), global_goal, tf_plan_to_global); tf2::doTransform(_global_plan.back(), global_goal, tf_plan_to_global);
double dx = global_goal.pose.position.x - _robot_pose.x(); double dx = global_goal.pose.position.x - _robot_pose.x();
@ -329,7 +380,7 @@ uint32_t MpcLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseSt
return mbf_msgs::ExePathResult::SUCCESS; return mbf_msgs::ExePathResult::SUCCESS;
} }
// Return false if the transformed global plan is empty // 如果转换后的全局计划为空则返回false
if (transformed_plan.empty()) if (transformed_plan.empty())
{ {
ROS_WARN("Transformed plan is empty. Cannot determine a local plan."); ROS_WARN("Transformed plan is empty. Cannot determine a local plan.");
@ -337,14 +388,14 @@ uint32_t MpcLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseSt
return mbf_msgs::ExePathResult::INVALID_PATH; return mbf_msgs::ExePathResult::INVALID_PATH;
} }
// Get current goal point (last point of the transformed plan) // 获取当前目标点(转换计划的最后一点)
_robot_goal.x() = transformed_plan.back().pose.position.x; _robot_goal.x() = transformed_plan.back().pose.position.x;
_robot_goal.y() = transformed_plan.back().pose.position.y; _robot_goal.y() = transformed_plan.back().pose.position.y;
// Overwrite goal orientation if needed // 如果需要,覆盖目标方向
if (_params.global_plan_overwrite_orientation) if (_params.global_plan_overwrite_orientation)
{ {
_robot_goal.theta() = estimateLocalGoalOrientation(_global_plan, transformed_plan.back(), goal_idx, tf_plan_to_global); _robot_goal.theta() = estimateLocalGoalOrientation(_global_plan, transformed_plan.back(), goal_idx, tf_plan_to_global);
// overwrite/update goal orientation of the transformed plan with the actual goal (enable using the plan as initialization) // 使用实际目标更新转换计划的目标方向(允许使用计划作为初始化)
tf2::Quaternion q; tf2::Quaternion q;
q.setRPY(0, 0, _robot_goal.theta()); q.setRPY(0, 0, _robot_goal.theta());
tf2::convert(q, transformed_plan.back().pose.orientation); tf2::convert(q, transformed_plan.back().pose.orientation);
@ -354,41 +405,41 @@ uint32_t MpcLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseSt
_robot_goal.theta() = tf2::getYaw(transformed_plan.back().pose.orientation); _robot_goal.theta() = tf2::getYaw(transformed_plan.back().pose.orientation);
} }
// overwrite/update start of the transformed plan with the actual robot position (allows using the plan as initial trajectory) // 使用实际的机器人位置覆盖转换计划的起点(允许使用计划作为初始轨迹)
if (transformed_plan.size() == 1) // plan only contains the goal if (transformed_plan.size() == 1) // plan only contains the goal
{ {
transformed_plan.insert(transformed_plan.begin(), geometry_msgs::PoseStamped()); // insert start (not yet initialized) transformed_plan.insert(transformed_plan.begin(), geometry_msgs::PoseStamped()); // insert start (not yet initialized)
} }
transformed_plan.front() = robot_pose; // update start transformed_plan.front() = robot_pose; // update start
// clear currently existing obstacles // 清除当前存在的障碍物
_obstacles.clear(); _obstacles.clear();
// Update obstacle container with costmap information or polygons provided by a costmap_converter plugin // 使用代价地图信息或由代价地图转换器插件提供的多边形更新障碍物容器
if (_costmap_converter) if (_costmap_converter)
updateObstacleContainerWithCostmapConverter(); updateObstacleContainerWithCostmapConverter();
else else
updateObstacleContainerWithCostmap(); updateObstacleContainerWithCostmap();
// also consider custom obstacles (must be called after other updates, since the container is not cleared) // 还需考虑自定义障碍物(必须在其他更新之后调用,因为容器未被清除)
updateObstacleContainerWithCustomObstacles(); updateObstacleContainerWithCustomObstacles();
// estimate current state vector and previous control // 估计当前状态向量和之前的控制
// updateControlFromTwist() // updateControlFromTwist()
// Do not allow config changes during the following optimization step // 在以下优化步骤期间不允许配置更改
boost::mutex::scoped_lock cfg_lock(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); // bool success = planner_->plan(transformed_plan, &robot_vel_, cfg_.goal_tolerance.free_goal_vel);
ros::Time t = ros::Time::now(); ros::Time t = ros::Time::now();
// controller_frequency might not be established in case planning takes longer: // 如果规划耗时较长,则可能未建立控制频率:
// value dt affects e.g. control deviation bounds (acceleration limits) and we want a goot start value // 值dt影响例如控制偏差界限加速度限制我们希望有一个好的起始值
// let's test how it works with the expected frequency instead of using the actual one // 让我们测试一下使用预期的频率而不是实际的频率效果如何
double dt = 1.0 / _params.controller_frequency; double dt = 1.0 / _params.controller_frequency;
// double dt = time_last_cmd_.isZero() ? 0.0 : (t - time_last_cmd_).toSec(); // double dt = time_last_cmd_.isZero() ? 0.0 : (t - time_last_cmd_).toSec();
// set previous control value for control deviation bounds // 设置前一个控制值以用于控制偏差界限
if (_u_seq && !_u_seq->isEmpty()) _controller.getOptimalControlProblem()->setPreviousControlInput(_u_seq->getValuesMap(0), dt); if (_u_seq && !_u_seq->isEmpty()) _controller.getOptimalControlProblem()->setPreviousControlInput(_u_seq->getValuesMap(0), dt);
bool success = false; bool success = false;
@ -401,20 +452,20 @@ uint32_t MpcLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseSt
if (!success) if (!success)
{ {
_controller.reset(); // force reinitialization for next time _controller.reset(); // 强制下次重新初始化
ROS_WARN("mpc_local_planner was not able to obtain a local plan for the current setting."); ROS_WARN("mpc_local_planner was not able to obtain a local plan for the current setting.");
++_no_infeasible_plans; // increase number of infeasible solutions in a row ++_no_infeasible_plans; // 增加连续不可行方案的数量
_time_last_infeasible_plan = ros::Time::now(); _time_last_infeasible_plan = ros::Time::now();
_last_cmd = cmd_vel.twist; _last_cmd = cmd_vel.twist;
message = "mpc_local_planner was not able to obtain a local plan"; message = "mpc_local_planner was not able to obtain a local plan";
return mbf_msgs::ExePathResult::NO_VALID_CMD; return mbf_msgs::ExePathResult::NO_VALID_CMD;
} }
// Check feasibility (but within the first few states only) // 检查可行性(但仅在前几个状态内)
if (_params.is_footprint_dynamic) if (_params.is_footprint_dynamic)
{ {
// Update footprint of the robot and minimum and maximum distance from the center of the robot to its footprint vertices. // 更新机器人的足迹,以及从机器人中心到其足迹顶点的最小和最大距离。
_footprint_spec = _costmap_ros->getRobotFootprint(); _footprint_spec = _costmap_ros->getRobotFootprint();
costmap_2d::calculateMinAndMaxDistances(_footprint_spec, _robot_inscribed_radius, _robot_circumscribed_radius); costmap_2d::calculateMinAndMaxDistances(_footprint_spec, _robot_inscribed_radius, _robot_circumscribed_radius);
} }
@ -425,41 +476,41 @@ uint32_t MpcLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseSt
{ {
cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0; cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0;
// now we reset everything to start again with the initialization of new trajectories. // 现在我们重置所有内容,以便下次重新初始化新轨迹。
_controller.reset(); // force reinitialization for next time _controller.reset(); // 强制下次重新初始化
ROS_WARN("MpcLocalPlannerROS: trajectory is not feasible. Resetting planner..."); ROS_WARN("MpcLocalPlannerROS: trajectory is not feasible. Resetting planner...");
++_no_infeasible_plans; // increase number of infeasible solutions in a row ++_no_infeasible_plans; // 增加连续不可行方案的数量
_time_last_infeasible_plan = ros::Time::now(); _time_last_infeasible_plan = ros::Time::now();
_last_cmd = cmd_vel.twist; _last_cmd = cmd_vel.twist;
message = "mpc_local_planner trajectory is not feasible"; message = "mpc_local_planner trajectory is not feasible";
return mbf_msgs::ExePathResult::NO_VALID_CMD; return mbf_msgs::ExePathResult::NO_VALID_CMD;
} }
// Get the velocity command for this sampling interval // 获取此采样间隔的速度命令
// TODO(roesmann): we might also command more than just the imminent action, e.g. in a separate thread, until a new command is available // TODO(roesmann):我们可能还会命令除即将采取的行动外的更多行动,例如在单独的线程中,直到有新命令可用为止
if (!_u_seq || !_controller.getRobotDynamics()->getTwistFromControl(_u_seq->getValuesMap(0), cmd_vel.twist)) if (!_u_seq || !_controller.getRobotDynamics()->getTwistFromControl(_u_seq->getValuesMap(0), cmd_vel.twist))
{ {
_controller.reset(); _controller.reset();
ROS_WARN("MpcLocalPlannerROS: velocity command invalid. Resetting controller..."); ROS_WARN("MpcLocalPlannerROS: velocity command invalid. Resetting controller...");
++_no_infeasible_plans; // increase number of infeasible solutions in a row ++_no_infeasible_plans; // 增加连续不可行方案的数量
_time_last_infeasible_plan = ros::Time::now(); _time_last_infeasible_plan = ros::Time::now();
_last_cmd = cmd_vel.twist; _last_cmd = cmd_vel.twist;
message = "mpc_local_planner velocity command invalid"; message = "mpc_local_planner velocity command invalid";
return mbf_msgs::ExePathResult::NO_VALID_CMD; return mbf_msgs::ExePathResult::NO_VALID_CMD;
} }
// Saturate velocity, if the optimization results violates the constraints (could be possible due to early termination or soft cosntraints). // 如果优化结果违反约束(可能由于提前终止或软约束),则限制速度。
// saturateVelocity(cmd_vel.twist.linear.x, cmd_vel.twist.linear.y, cmd_vel.twist.angular.z, cfg_.robot.max_vel_x, cfg_.robot.max_vel_y, // saturateVelocity(cmd_vel.twist.linear.x, cmd_vel.twist.linear.y, cmd_vel.twist.angular.z, cfg_.robot.max_vel_x, cfg_.robot.max_vel_y,
// cfg_.robot.max_vel_theta, cfg_.robot.max_vel_x_backwards); // cfg_.robot.max_vel_theta, cfg_.robot.max_vel_x_backwards);
// a feasible solution should be found, reset counter // 应找到可行的解决方案,重置计数器
_no_infeasible_plans = 0; _no_infeasible_plans = 0;
// store last command (for recovery analysis etc.) // 存储最后一个命令(用于恢复分析等)
_last_cmd = cmd_vel.twist; _last_cmd = cmd_vel.twist;
_time_last_cmd = ros::Time::now(); _time_last_cmd = ros::Time::now();
// Now visualize everything // 现在可视化所有内容
_publisher.publishLocalPlan(*_x_seq); _publisher.publishLocalPlan(*_x_seq);
_publisher.publishObstacles(_obstacles); _publisher.publishObstacles(_obstacles);
_publisher.publishGlobalPlan(_global_plan); _publisher.publishGlobalPlan(_global_plan);
@ -468,6 +519,13 @@ uint32_t MpcLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseSt
return mbf_msgs::ExePathResult::SUCCESS; return mbf_msgs::ExePathResult::SUCCESS;
} }
/**
* @brief
*
*
*
* @return bool truefalse
*/
bool MpcLocalPlannerROS::isGoalReached() bool MpcLocalPlannerROS::isGoalReached()
{ {
if (_goal_reached) if (_goal_reached)
@ -479,6 +537,11 @@ bool MpcLocalPlannerROS::isGoalReached()
return false; return false;
} }
/**
* @brief 使
*
*
*/
void MpcLocalPlannerROS::updateObstacleContainerWithCostmap() void MpcLocalPlannerROS::updateObstacleContainerWithCostmap()
{ {
// Add costmap obstacles if desired // Add costmap obstacles if desired
@ -495,7 +558,7 @@ void MpcLocalPlannerROS::updateObstacleContainerWithCostmap()
Eigen::Vector2d obs; Eigen::Vector2d obs;
_costmap->mapToWorld(i, j, obs.coeffRef(0), obs.coeffRef(1)); _costmap->mapToWorld(i, j, obs.coeffRef(0), obs.coeffRef(1));
// check if obstacle is interesting (e.g. not far behind the robot) // 检查障碍物是否在机器人前方(例如,不远离机器人)
Eigen::Vector2d obs_dir = obs - _robot_pose.position(); Eigen::Vector2d obs_dir = obs - _robot_pose.position();
if (obs_dir.dot(robot_orient) < 0 && obs_dir.norm() > _params.costmap_obstacles_behind_robot_dist) continue; if (obs_dir.dot(robot_orient) < 0 && obs_dir.norm() > _params.costmap_obstacles_behind_robot_dist) continue;
@ -506,11 +569,16 @@ void MpcLocalPlannerROS::updateObstacleContainerWithCostmap()
} }
} }
/**
* @brief 使
*
*
*/
void MpcLocalPlannerROS::updateObstacleContainerWithCostmapConverter() void MpcLocalPlannerROS::updateObstacleContainerWithCostmapConverter()
{ {
if (!_costmap_converter) return; if (!_costmap_converter) return;
// Get obstacles from costmap converter // 从代价地图转换器获取障碍物
costmap_converter::ObstacleArrayConstPtr obstacles = _costmap_converter->getObstacles(); costmap_converter::ObstacleArrayConstPtr obstacles = _costmap_converter->getObstacles();
if (!obstacles) return; if (!obstacles) return;
@ -519,20 +587,20 @@ void MpcLocalPlannerROS::updateObstacleContainerWithCostmapConverter()
const costmap_converter::ObstacleMsg* obstacle = &obstacles->obstacles.at(i); const costmap_converter::ObstacleMsg* obstacle = &obstacles->obstacles.at(i);
const geometry_msgs::Polygon* polygon = &obstacle->polygon; const geometry_msgs::Polygon* polygon = &obstacle->polygon;
if (polygon->points.size() == 1 && obstacle->radius > 0) // Circle if (polygon->points.size() == 1 && obstacle->radius > 0) // 圆形
{ {
_obstacles.push_back(ObstaclePtr(new CircularObstacle(polygon->points[0].x, polygon->points[0].y, obstacle->radius))); _obstacles.push_back(ObstaclePtr(new CircularObstacle(polygon->points[0].x, polygon->points[0].y, obstacle->radius)));
} }
else if (polygon->points.size() == 1) // Point else if (polygon->points.size() == 1) //
{ {
_obstacles.push_back(ObstaclePtr(new PointObstacle(polygon->points[0].x, polygon->points[0].y))); _obstacles.push_back(ObstaclePtr(new PointObstacle(polygon->points[0].x, polygon->points[0].y)));
} }
else if (polygon->points.size() == 2) // Line else if (polygon->points.size() == 2) // 线
{ {
_obstacles.push_back( _obstacles.push_back(
ObstaclePtr(new LineObstacle(polygon->points[0].x, polygon->points[0].y, polygon->points[1].x, polygon->points[1].y))); ObstaclePtr(new LineObstacle(polygon->points[0].x, polygon->points[0].y, polygon->points[1].x, polygon->points[1].y)));
} }
else if (polygon->points.size() > 2) // Real polygon else if (polygon->points.size() > 2) // 多边形
{ {
PolygonObstacle* polyobst = new PolygonObstacle; PolygonObstacle* polyobst = new PolygonObstacle;
for (std::size_t j = 0; j < polygon->points.size(); ++j) for (std::size_t j = 0; j < polygon->points.size(); ++j)
@ -543,19 +611,24 @@ void MpcLocalPlannerROS::updateObstacleContainerWithCostmapConverter()
_obstacles.push_back(ObstaclePtr(polyobst)); _obstacles.push_back(ObstaclePtr(polyobst));
} }
// Set velocity, if obstacle is moving // 如果障碍物在移动,设置速度
if (!_obstacles.empty()) _obstacles.back()->setCentroidVelocity(obstacles->obstacles[i].velocities, obstacles->obstacles[i].orientation); if (!_obstacles.empty()) _obstacles.back()->setCentroidVelocity(obstacles->obstacles[i].velocities, obstacles->obstacles[i].orientation);
} }
} }
/**
* @brief 使
*
*
*/
void MpcLocalPlannerROS::updateObstacleContainerWithCustomObstacles() void MpcLocalPlannerROS::updateObstacleContainerWithCustomObstacles()
{ {
// Add custom obstacles obtained via message // 添加通过消息获得的自定义障碍物
std::lock_guard<std::mutex> l(_custom_obst_mutex); std::lock_guard<std::mutex> l(_custom_obst_mutex);
if (!_custom_obstacle_msg.obstacles.empty()) if (!_custom_obstacle_msg.obstacles.empty())
{ {
// We only use the global header to specify the obstacle coordinate system instead of individual ones // 我们只使用全局header来指定障碍物坐标系而不是单独的header
Eigen::Affine3d obstacle_to_map_eig; Eigen::Affine3d obstacle_to_map_eig;
try try
{ {
@ -617,13 +690,21 @@ void MpcLocalPlannerROS::updateObstacleContainerWithCustomObstacles()
_obstacles.push_back(ObstaclePtr(polyobst)); _obstacles.push_back(ObstaclePtr(polyobst));
} }
// Set velocity, if obstacle is moving // 如果障碍物在移动,设置速度
if (!_obstacles.empty()) if (!_obstacles.empty())
_obstacles.back()->setCentroidVelocity(_custom_obstacle_msg.obstacles[i].velocities, _custom_obstacle_msg.obstacles[i].orientation); _obstacles.back()->setCentroidVelocity(_custom_obstacle_msg.obstacles[i].velocities, _custom_obstacle_msg.obstacles[i].orientation);
} }
} }
} }
/**
* @brief
*
*
*
* @param transformed_plan
* @param min_separation
*/
void MpcLocalPlannerROS::updateViaPointsContainer(const std::vector<geometry_msgs::PoseStamped>& transformed_plan, double min_separation) void MpcLocalPlannerROS::updateViaPointsContainer(const std::vector<geometry_msgs::PoseStamped>& transformed_plan, double min_separation)
{ {
_via_points.clear(); _via_points.clear();
@ -631,17 +712,25 @@ void MpcLocalPlannerROS::updateViaPointsContainer(const std::vector<geometry_msg
if (min_separation <= 0) return; if (min_separation <= 0) return;
std::size_t prev_idx = 0; std::size_t prev_idx = 0;
for (std::size_t i = 1; i < transformed_plan.size(); ++i) // skip first one, since we do not need any point before the first min_separation [m] for (std::size_t i = 1; i < transformed_plan.size(); ++i) // 跳过第一个点因为我们不需要在第一个min_separation [m] 之前的任何点
{ {
// check separation to the previous via-point inserted // 检查与前一个路径点的间隔
if (distance_points2d(transformed_plan[prev_idx].pose.position, transformed_plan[i].pose.position) < min_separation) continue; if (distance_points2d(transformed_plan[prev_idx].pose.position, transformed_plan[i].pose.position) < min_separation) continue;
// add via-point /// 添加路径点
_via_points.emplace_back(transformed_plan[i].pose); _via_points.emplace_back(transformed_plan[i].pose);
prev_idx = i; prev_idx = i;
} }
} }
/**
* @brief tf::PoseEigen::Vector2d
*
* tf::PoseEigen::Vector2d
*
* @param tf_vel tf::Pose
* @return Eigen::Vector2d
*/
Eigen::Vector2d MpcLocalPlannerROS::tfPoseToEigenVector2dTransRot(const tf::Pose& tf_vel) Eigen::Vector2d MpcLocalPlannerROS::tfPoseToEigenVector2dTransRot(const tf::Pose& tf_vel)
{ {
Eigen::Vector2d vel; Eigen::Vector2d vel;
@ -650,6 +739,17 @@ Eigen::Vector2d MpcLocalPlannerROS::tfPoseToEigenVector2dTransRot(const tf::Pose
return vel; return vel;
} }
/**
* @brief
*
*
*
* @param tf TF
* @param global_pose 姿
* @param global_plan
* @param dist_behind_robot
* @return bool truefalse
*/
bool MpcLocalPlannerROS::pruneGlobalPlan(const tf2_ros::Buffer& tf, const geometry_msgs::PoseStamped& global_pose, bool MpcLocalPlannerROS::pruneGlobalPlan(const tf2_ros::Buffer& tf, const geometry_msgs::PoseStamped& global_pose,
std::vector<geometry_msgs::PoseStamped>& global_plan, double dist_behind_robot) std::vector<geometry_msgs::PoseStamped>& global_plan, double dist_behind_robot)
{ {
@ -657,7 +757,7 @@ bool MpcLocalPlannerROS::pruneGlobalPlan(const tf2_ros::Buffer& tf, const geomet
try try
{ {
// transform robot pose into the plan frame (we do not wait here, since pruning not crucial, if missed a few times) // 将机器人位姿转换到计划的参考框架(这里不等待,因为即使错过几次修剪也不会有大问题)
geometry_msgs::TransformStamped global_to_plan_transform = geometry_msgs::TransformStamped global_to_plan_transform =
tf.lookupTransform(global_plan.front().header.frame_id, global_pose.header.frame_id, ros::Time(0)); tf.lookupTransform(global_plan.front().header.frame_id, global_pose.header.frame_id, ros::Time(0));
geometry_msgs::PoseStamped robot; geometry_msgs::PoseStamped robot;
@ -665,7 +765,7 @@ bool MpcLocalPlannerROS::pruneGlobalPlan(const tf2_ros::Buffer& tf, const geomet
double dist_thresh_sq = dist_behind_robot * dist_behind_robot; double dist_thresh_sq = dist_behind_robot * dist_behind_robot;
// iterate plan until a pose close the robot is found // 迭代计划,直到找到一个接近机器人的路径点
std::vector<geometry_msgs::PoseStamped>::iterator it = global_plan.begin(); std::vector<geometry_msgs::PoseStamped>::iterator it = global_plan.begin();
std::vector<geometry_msgs::PoseStamped>::iterator erase_end = it; std::vector<geometry_msgs::PoseStamped>::iterator erase_end = it;
while (it != global_plan.end()) while (it != global_plan.end())
@ -692,13 +792,29 @@ bool MpcLocalPlannerROS::pruneGlobalPlan(const tf2_ros::Buffer& tf, const geomet
return true; return true;
} }
/**
* @brief
*
*
*
* @param tf TF
* @param global_plan
* @param global_pose 姿
* @param costmap
* @param global_frame
* @param max_plan_length
* @param transformed_plan
* @param current_goal_idx
* @param tf_plan_to_global
* @return bool truefalse
*/
bool MpcLocalPlannerROS::transformGlobalPlan(const tf2_ros::Buffer& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan, bool MpcLocalPlannerROS::transformGlobalPlan(const tf2_ros::Buffer& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
const geometry_msgs::PoseStamped& global_pose, const costmap_2d::Costmap2D& costmap, const geometry_msgs::PoseStamped& global_pose, const costmap_2d::Costmap2D& costmap,
const std::string& global_frame, double max_plan_length, const std::string& global_frame, double max_plan_length,
std::vector<geometry_msgs::PoseStamped>& transformed_plan, int* current_goal_idx, std::vector<geometry_msgs::PoseStamped>& transformed_plan, int* current_goal_idx,
geometry_msgs::TransformStamped* tf_plan_to_global) const geometry_msgs::TransformStamped* tf_plan_to_global) const
{ {
// this method is a slightly modified version of base_local_planner/goal_functions.h // 该方法是 base_local_planner/goal_functions.h 的稍作修改版本
const geometry_msgs::PoseStamped& plan_pose = global_plan[0]; const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
@ -713,33 +829,32 @@ bool MpcLocalPlannerROS::transformGlobalPlan(const tf2_ros::Buffer& tf, const st
return false; return false;
} }
// get plan_to_global_transform from plan frame to global_frame // 从计划框架到全局框架的变换
geometry_msgs::TransformStamped plan_to_global_transform = tf.lookupTransform( geometry_msgs::TransformStamped plan_to_global_transform = tf.lookupTransform(
global_frame, ros::Time(), plan_pose.header.frame_id, plan_pose.header.stamp, plan_pose.header.frame_id, ros::Duration(0.5)); global_frame, ros::Time(), plan_pose.header.frame_id, plan_pose.header.stamp, plan_pose.header.frame_id, ros::Duration(0.5));
// let's get the pose of the robot in the frame of the plan // 获取机器人在计划框架中的位姿
geometry_msgs::PoseStamped robot_pose; geometry_msgs::PoseStamped robot_pose;
tf.transform(global_pose, robot_pose, plan_pose.header.frame_id); tf.transform(global_pose, robot_pose, plan_pose.header.frame_id);
// we'll discard points on the plan that are outside the local costmap // 丢弃计划中超出局部代价地图的点
double dist_threshold = double dist_threshold =
std::max(costmap.getSizeInCellsX() * costmap.getResolution() / 2.0, costmap.getSizeInCellsY() * costmap.getResolution() / 2.0); std::max(costmap.getSizeInCellsX() * costmap.getResolution() / 2.0, costmap.getSizeInCellsY() * costmap.getResolution() / 2.0);
dist_threshold *= 0.85; // just consider 85% of the costmap size to better incorporate point obstacle that are dist_threshold *= 0.85; // 仅考虑代价地图大小的85%,以更好地纳入位于局部代价地图边界上的点障碍物
// located on the border of the local costmap
int i = 0; int i = 0;
double sq_dist_threshold = dist_threshold * dist_threshold; double sq_dist_threshold = dist_threshold * dist_threshold;
double sq_dist = 1e10; double sq_dist = 1e10;
// we need to loop to a point on the plan that is within a certain distance of the robot // 我们需要循环直到找到一个距离机器人一定距离内的计划点
for (int j = 0; j < (int)global_plan.size(); ++j) for (int j = 0; j < (int)global_plan.size(); ++j)
{ {
double x_diff = robot_pose.pose.position.x - global_plan[j].pose.position.x; double x_diff = robot_pose.pose.position.x - global_plan[j].pose.position.x;
double y_diff = robot_pose.pose.position.y - global_plan[j].pose.position.y; double y_diff = robot_pose.pose.position.y - global_plan[j].pose.position.y;
double new_sq_dist = x_diff * x_diff + y_diff * y_diff; double new_sq_dist = x_diff * x_diff + y_diff * y_diff;
if (new_sq_dist > sq_dist_threshold) break; // force stop if we have reached the costmap border if (new_sq_dist > sq_dist_threshold) break; // 如果已到达代价地图边界,则强制停止
if (new_sq_dist < sq_dist) // find closest distance if (new_sq_dist < sq_dist) // 找到最近距离
{ {
sq_dist = new_sq_dist; sq_dist = new_sq_dist;
i = j; i = j;
@ -748,9 +863,9 @@ bool MpcLocalPlannerROS::transformGlobalPlan(const tf2_ros::Buffer& tf, const st
geometry_msgs::PoseStamped newer_pose; geometry_msgs::PoseStamped newer_pose;
double plan_length = 0; // check cumulative Euclidean distance along the plan double plan_length = 0; // 检查沿计划的累计欧几里得距离
// now we'll transform until points are outside of our distance threshold // 现在我们将转换,直到点超出我们的距离阈值
while (i < (int)global_plan.size() && sq_dist <= sq_dist_threshold && (max_plan_length <= 0 || plan_length <= max_plan_length)) while (i < (int)global_plan.size() && sq_dist <= sq_dist_threshold && (max_plan_length <= 0 || plan_length <= max_plan_length))
{ {
const geometry_msgs::PoseStamped& pose = global_plan[i]; const geometry_msgs::PoseStamped& pose = global_plan[i];
@ -762,31 +877,30 @@ bool MpcLocalPlannerROS::transformGlobalPlan(const tf2_ros::Buffer& tf, const st
double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y; double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y;
sq_dist = x_diff * x_diff + y_diff * y_diff; sq_dist = x_diff * x_diff + y_diff * y_diff;
// caclulate distance to previous pose // 计算与前一个位姿的距离
if (i > 0 && max_plan_length > 0) if (i > 0 && max_plan_length > 0)
plan_length += teb_local_planner::distance_points2d(global_plan[i - 1].pose.position, global_plan[i].pose.position); plan_length += teb_local_planner::distance_points2d(global_plan[i - 1].pose.position, global_plan[i].pose.position);
++i; ++i;
} }
// if we are really close to the goal (<sq_dist_threshold) and the goal is not yet reached (e.g. orientation error >>0) // 如果我们非常接近目标(<sq_dist_threshold),但目标尚未到达(例如方向误差>>0则结果转换计划可能为空。在这种情况下我们显式注入全局目标。
// the resulting transformed plan can be empty. In that case we explicitly inject the global goal.
if (transformed_plan.empty()) if (transformed_plan.empty())
{ {
tf2::doTransform(global_plan.back(), newer_pose, plan_to_global_transform); tf2::doTransform(global_plan.back(), newer_pose, plan_to_global_transform);
transformed_plan.push_back(newer_pose); transformed_plan.push_back(newer_pose);
// Return the index of the current goal point (inside the distance threshold) // 返回当前目标点的索引(在距离阈值内)
if (current_goal_idx) *current_goal_idx = int(global_plan.size()) - 1; if (current_goal_idx) *current_goal_idx = int(global_plan.size()) - 1;
} }
else else
{ {
// Return the index of the current goal point (inside the distance threshold) // 返回当前目标点的索引(在距离阈值内)
if (current_goal_idx) *current_goal_idx = i - 1; // subtract 1, since i was increased once before leaving the loop if (current_goal_idx) *current_goal_idx = i - 1; // 减去1因为在离开循环前i增加了一次
} }
// Return the transformation from the global plan to the global planning frame if desired // 如果需要,返回从全局计划到全局规划框架的变换
if (tf_plan_to_global) *tf_plan_to_global = plan_to_global_transform; if (tf_plan_to_global) *tf_plan_to_global = plan_to_global_transform;
} }
catch (tf::LookupException& ex) catch (tf::LookupException& ex)
@ -812,16 +926,28 @@ bool MpcLocalPlannerROS::transformGlobalPlan(const tf2_ros::Buffer& tf, const st
return true; return true;
} }
/**
* @brief
*
*
*
* @param global_plan
* @param local_goal
* @param current_goal_idx
* @param tf_plan_to_global
* @param moving_average_length
* @return double
*/
double MpcLocalPlannerROS::estimateLocalGoalOrientation(const std::vector<geometry_msgs::PoseStamped>& global_plan, double MpcLocalPlannerROS::estimateLocalGoalOrientation(const std::vector<geometry_msgs::PoseStamped>& global_plan,
const geometry_msgs::PoseStamped& local_goal, int current_goal_idx, const geometry_msgs::PoseStamped& local_goal, int current_goal_idx,
const geometry_msgs::TransformStamped& tf_plan_to_global, int moving_average_length) const const geometry_msgs::TransformStamped& tf_plan_to_global, int moving_average_length) const
{ {
int n = (int)global_plan.size(); int n = (int)global_plan.size();
// check if we are near the global goal already // 检查是否已接近全局目标
if (current_goal_idx > n - moving_average_length - 2) if (current_goal_idx > n - moving_average_length - 2)
{ {
if (current_goal_idx >= n - 1) // we've exactly reached the goal if (current_goal_idx >= n - 1) // 刚好到达目标
{ {
return tf2::getYaw(local_goal.pose.orientation); return tf2::getYaw(local_goal.pose.orientation);
} }
@ -831,14 +957,14 @@ double MpcLocalPlannerROS::estimateLocalGoalOrientation(const std::vector<geomet
tf2::convert(global_plan.back().pose.orientation, global_orientation); tf2::convert(global_plan.back().pose.orientation, global_orientation);
tf2::Quaternion rotation; tf2::Quaternion rotation;
tf2::convert(tf_plan_to_global.transform.rotation, rotation); tf2::convert(tf_plan_to_global.transform.rotation, rotation);
// TODO(roesmann): avoid conversion to tf2::Quaternion // TODO(roesmann): 避免转换为 tf2::Quaternion
return tf2::getYaw(rotation * global_orientation); return tf2::getYaw(rotation * global_orientation);
} }
} }
// reduce number of poses taken into account if the desired number of poses is not available // 如果所需的位姿数不可用,则减少考虑的位姿数
moving_average_length = moving_average_length =
std::min(moving_average_length, n - current_goal_idx - 1); // maybe redundant, since we have checked the vicinity of the goal before std::min(moving_average_length, n - current_goal_idx - 1); // 可能是多余的,因为我们之前已经检查了目标的附近
std::vector<double> candidates; std::vector<double> candidates;
geometry_msgs::PoseStamped tf_pose_k = local_goal; geometry_msgs::PoseStamped tf_pose_k = local_goal;
@ -847,10 +973,10 @@ double MpcLocalPlannerROS::estimateLocalGoalOrientation(const std::vector<geomet
int range_end = current_goal_idx + moving_average_length; int range_end = current_goal_idx + moving_average_length;
for (int i = current_goal_idx; i < range_end; ++i) for (int i = current_goal_idx; i < range_end; ++i)
{ {
// Transform pose of the global plan to the planning frame // 将全局计划的位姿转换为规划框架
tf2::doTransform(global_plan.at(i + 1), tf_pose_kp1, tf_plan_to_global); tf2::doTransform(global_plan.at(i + 1), tf_pose_kp1, tf_plan_to_global);
// calculate yaw angle // 计算偏航角
candidates.push_back( candidates.push_back(
std::atan2(tf_pose_kp1.pose.position.y - tf_pose_k.pose.position.y, tf_pose_kp1.pose.position.x - tf_pose_k.pose.position.x)); std::atan2(tf_pose_kp1.pose.position.y - tf_pose_k.pose.position.y, tf_pose_kp1.pose.position.x - tf_pose_k.pose.position.x));
@ -859,6 +985,16 @@ double MpcLocalPlannerROS::estimateLocalGoalOrientation(const std::vector<geomet
return teb_local_planner::average_angles(candidates); return teb_local_planner::average_angles(candidates);
} }
/**
* @brief
*
*
*
* @param opt_inscribed_radius
* @param costmap_inscribed_radius
* @param min_obst_dist
*/
void MpcLocalPlannerROS::validateFootprints(double opt_inscribed_radius, double costmap_inscribed_radius, double min_obst_dist) void MpcLocalPlannerROS::validateFootprints(double opt_inscribed_radius, double costmap_inscribed_radius, double min_obst_dist)
{ {
ROS_WARN_COND(opt_inscribed_radius + min_obst_dist < costmap_inscribed_radius, ROS_WARN_COND(opt_inscribed_radius + min_obst_dist < costmap_inscribed_radius,
@ -868,12 +1004,26 @@ void MpcLocalPlannerROS::validateFootprints(double opt_inscribed_radius, double
opt_inscribed_radius, min_obst_dist, costmap_inscribed_radius); opt_inscribed_radius, min_obst_dist, costmap_inscribed_radius);
} }
/**
* @brief
*
*
*
* @param obst_msg
*/
void MpcLocalPlannerROS::customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg) void MpcLocalPlannerROS::customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg)
{ {
std::lock_guard<std::mutex> l(_custom_obst_mutex); std::lock_guard<std::mutex> l(_custom_obst_mutex);
_custom_obstacle_msg = *obst_msg; _custom_obstacle_msg = *obst_msg;
} }
/**
* @brief
*
*
*
* @param via_points_msg
*/
void MpcLocalPlannerROS::customViaPointsCB(const nav_msgs::Path::ConstPtr& via_points_msg) void MpcLocalPlannerROS::customViaPointsCB(const nav_msgs::Path::ConstPtr& via_points_msg)
{ {
ROS_INFO_ONCE("Via-points received. This message is printed once."); ROS_INFO_ONCE("Via-points received. This message is printed once.");
@ -895,6 +1045,15 @@ void MpcLocalPlannerROS::customViaPointsCB(const nav_msgs::Path::ConstPtr& via_p
_custom_via_points_active = !_via_points.empty(); _custom_via_points_active = !_via_points.empty();
} }
/**
* @brief
*
*
*
* @param nh ROS
* @param costmap_ros costmap_2d::Costmap2DROS
* @return teb_local_planner::RobotFootprintModelPtr
*/
teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintFromParamServer(const ros::NodeHandle& nh, teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintFromParamServer(const ros::NodeHandle& nh,
costmap_2d::Costmap2DROS* costmap_ros) costmap_2d::Costmap2DROS* costmap_ros)
{ {
@ -905,7 +1064,7 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
return boost::make_shared<teb_local_planner::PointRobotFootprint>(); return boost::make_shared<teb_local_planner::PointRobotFootprint>();
} }
// from costmap_2d // 从costmap_2d获取
if (model_name.compare("costmap_2d") == 0) if (model_name.compare("costmap_2d") == 0)
{ {
if (!costmap_ros) if (!costmap_ros)
@ -917,17 +1076,17 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
return getRobotFootprintFromCostmap2d(*costmap_ros); return getRobotFootprintFromCostmap2d(*costmap_ros);
} }
// point // 点模型
if (model_name.compare("point") == 0) if (model_name.compare("point") == 0)
{ {
ROS_INFO("Footprint model 'point' loaded for trajectory optimization."); ROS_INFO("Footprint model 'point' loaded for trajectory optimization.");
return boost::make_shared<teb_local_planner::PointRobotFootprint>(); return boost::make_shared<teb_local_planner::PointRobotFootprint>();
} }
// circular // 圆形模型
if (model_name.compare("circular") == 0) if (model_name.compare("circular") == 0)
{ {
// get radius // 获取半径
double radius; double radius;
if (!nh.getParam("footprint_model/radius", radius)) if (!nh.getParam("footprint_model/radius", radius))
{ {
@ -939,17 +1098,17 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
return boost::make_shared<teb_local_planner::CircularRobotFootprint>(radius); return boost::make_shared<teb_local_planner::CircularRobotFootprint>(radius);
} }
// line // 线模型
if (model_name.compare("line") == 0) if (model_name.compare("line") == 0)
{ {
// check parameters // 检查参数
if (!nh.hasParam("footprint_model/line_start") || !nh.hasParam("footprint_model/line_end")) if (!nh.hasParam("footprint_model/line_start") || !nh.hasParam("footprint_model/line_end"))
{ {
ROS_ERROR_STREAM("Footprint model 'line' cannot be loaded for trajectory optimization, since param '" ROS_ERROR_STREAM("Footprint model 'line' cannot be loaded for trajectory optimization, since param '"
<< nh.getNamespace() << "/footprint_model/line_start' and/or '.../line_end' do not exist. Using point-model instead."); << nh.getNamespace() << "/footprint_model/line_start' and/or '.../line_end' do not exist. Using point-model instead.");
return boost::make_shared<teb_local_planner::PointRobotFootprint>(); return boost::make_shared<teb_local_planner::PointRobotFootprint>();
} }
// get line coordinates // 获取线坐标
std::vector<double> line_start, line_end; std::vector<double> line_start, line_end;
nh.getParam("footprint_model/line_start", line_start); nh.getParam("footprint_model/line_start", line_start);
nh.getParam("footprint_model/line_end", line_end); nh.getParam("footprint_model/line_end", line_end);
@ -968,10 +1127,10 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
Eigen::Map<const Eigen::Vector2d>(line_end.data())); Eigen::Map<const Eigen::Vector2d>(line_end.data()));
} }
// two circles // 两个圆形
if (model_name.compare("two_circles") == 0) if (model_name.compare("two_circles") == 0)
{ {
// check parameters // 检查参数
if (!nh.hasParam("footprint_model/front_offset") || !nh.hasParam("footprint_model/front_radius") || if (!nh.hasParam("footprint_model/front_offset") || !nh.hasParam("footprint_model/front_radius") ||
!nh.hasParam("footprint_model/rear_offset") || !nh.hasParam("footprint_model/rear_radius")) !nh.hasParam("footprint_model/rear_offset") || !nh.hasParam("footprint_model/rear_radius"))
{ {
@ -992,11 +1151,11 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
return boost::make_shared<teb_local_planner::TwoCirclesRobotFootprint>(front_offset, front_radius, rear_offset, rear_radius); return boost::make_shared<teb_local_planner::TwoCirclesRobotFootprint>(front_offset, front_radius, rear_offset, rear_radius);
} }
// polygon // 多边形
if (model_name.compare("polygon") == 0) if (model_name.compare("polygon") == 0)
{ {
// check parameters // 检查参数
XmlRpc::XmlRpcValue footprint_xmlrpc; XmlRpc::XmlRpcValue footprint_xmlrpc;
if (!nh.getParam("footprint_model/vertices", footprint_xmlrpc)) if (!nh.getParam("footprint_model/vertices", footprint_xmlrpc))
{ {
@ -1004,7 +1163,7 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
<< nh.getNamespace() << "/footprint_model/vertices' does not exist. Using point-model instead."); << nh.getNamespace() << "/footprint_model/vertices' does not exist. Using point-model instead.");
return boost::make_shared<teb_local_planner::PointRobotFootprint>(); return boost::make_shared<teb_local_planner::PointRobotFootprint>();
} }
// get vertices // 获取顶点
if (footprint_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeArray) if (footprint_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeArray)
{ {
try try
@ -1029,12 +1188,20 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
} }
} }
// otherwise // 其他情况
ROS_WARN_STREAM("Unknown robot footprint model specified with parameter '" << nh.getNamespace() ROS_WARN_STREAM("Unknown robot footprint model specified with parameter '" << nh.getNamespace()
<< "/footprint_model/type'. Using point model instead."); << "/footprint_model/type'. Using point model instead.");
return boost::make_shared<teb_local_planner::PointRobotFootprint>(); return boost::make_shared<teb_local_planner::PointRobotFootprint>();
} }
/**
* @brief costmap_2d
*
* costmap_2d::Costmap2DROSteb_local_planner
*
* @param costmap_ros costmap_2d::Costmap2DROS
* @return teb_local_planner::RobotFootprintModelPtr
*/
teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintFromCostmap2d(costmap_2d::Costmap2DROS& costmap_ros) teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintFromCostmap2d(costmap_2d::Costmap2DROS& costmap_ros)
{ {
Point2dContainer footprint; Point2dContainer footprint;
@ -1051,10 +1218,20 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
return boost::make_shared<teb_local_planner::PolygonRobotFootprint>(footprint); return boost::make_shared<teb_local_planner::PolygonRobotFootprint>(footprint);
} }
/**
* @brief XMLRPC
*
* XMLRPCPoint2dContainer
*
* @param footprint_xmlrpc XMLRPC
* @param full_param_name
* @return teb_local_planner::Point2dContainer Point2dContainer
*/
teb_local_planner::Point2dContainer MpcLocalPlannerROS::makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue& footprint_xmlrpc, teb_local_planner::Point2dContainer MpcLocalPlannerROS::makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue& footprint_xmlrpc,
const std::string& full_param_name) const std::string& full_param_name)
{ {
// Make sure we have an array of at least 3 elements. // 确保我们有至少包含3个元素的数组
if (footprint_xmlrpc.getType() != XmlRpc::XmlRpcValue::TypeArray || footprint_xmlrpc.size() < 3) if (footprint_xmlrpc.getType() != XmlRpc::XmlRpcValue::TypeArray || footprint_xmlrpc.size() < 3)
{ {
ROS_FATAL("The footprint must be specified as list of lists on the parameter server, %s was specified as %s", full_param_name.c_str(), ROS_FATAL("The footprint must be specified as list of lists on the parameter server, %s was specified as %s", full_param_name.c_str(),
@ -1069,7 +1246,7 @@ teb_local_planner::Point2dContainer MpcLocalPlannerROS::makeFootprintFromXMLRPC(
for (int i = 0; i < footprint_xmlrpc.size(); ++i) for (int i = 0; i < footprint_xmlrpc.size(); ++i)
{ {
// Make sure each element of the list is an array of size 2. (x and y coordinates) // 确保列表中的每个元素都是包含2个元素的数组x和y坐标
XmlRpc::XmlRpcValue point = footprint_xmlrpc[i]; XmlRpc::XmlRpcValue point = footprint_xmlrpc[i];
if (point.getType() != XmlRpc::XmlRpcValue::TypeArray || point.size() != 2) if (point.getType() != XmlRpc::XmlRpcValue::TypeArray || point.size() != 2)
{ {
@ -1090,6 +1267,15 @@ teb_local_planner::Point2dContainer MpcLocalPlannerROS::makeFootprintFromXMLRPC(
return footprint; return footprint;
} }
/**
* @brief XMLRPC
*
* XMLRPCintdouble
*
* @param value XMLRPC
* @param full_param_name
* @return double
*/
double MpcLocalPlannerROS::getNumberFromXMLRPC(XmlRpc::XmlRpcValue& value, const std::string& full_param_name) double MpcLocalPlannerROS::getNumberFromXMLRPC(XmlRpc::XmlRpcValue& value, const std::string& full_param_name)
{ {
// Make sure that the value we're looking at is either a double or an int. // Make sure that the value we're looking at is either a double or an int.