紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
8.2.2代码报错:没有参数匹配的重载函数“nav2_util"
-
代码报错问题:
没有与参数列表匹配的 重载函数 "nav2_util::declare_parameter_if_not_declared" 实例
空间构建错误:
#ifndef NAV2_CUSTOM_PLANNER__NAV2_CUSTOM_PLANNER_HPP_ #define NAV2_CUSTOM_PLANNER__NAV2_CUSTOM_PLANNER_HPP_ #include <memory> #include <string> #include "geometry_msgs/msg/point.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "rclcpp/rclcpp.hpp" #include "nav2_core/global_planner.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_util/lifecycle_node.hpp" #include "nav2_util/robot_utils.hpp" #include "nav_msgs/msg/path.hpp" namespace nav2_custom_planner { //自定义导航规划器类 class CustomPlanner : public nav2_core::GlobalPlanner{ public: CustomPlanner() = default; ~CustomPlanner() = default; //插件配置方法 void configure( const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr<tf2_ros::Buffer> tf, std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override; //插件清理的方法 void cleanup() override; //插件激活的方法 void activate() override; //插件停用的方法 void deactivate() override; //为给定的起始和目标位姿创建路径的方法 nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal) override; private: //坐标变换缓存指针,可用于查询坐标关系 std::shared_ptr<tf2_ros::Buffer> tf_; //节点指针 nav2_util::LifecycleNode::SharedPtr node_; //全局代价地图 nav2_costmap_2d::Costmap2D *costmap_; //全局代价地图的坐标系 std::string global_frame_, name_; //插值分辨率 double interpolation_resolution_; }; } // namespace nav2_custom_planner #endif // NAV2_CUSTOM_PLANNER__NAV2_CUSTOM_PLANNER_HPP_
nav2_custom_planner.cpp代码:
#include "nav2_util/node_utils.hpp" #include <cmath> #include <memory> #include <string> #include "nav2_core/exceptions.hpp" #include "nav2_custom_planner/nav2_custom_planner.hpp" namespace nav2_custom_planner{ void CustomPlanner::configure( const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr<tf2_ros::Buffer> tf, std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) { tf_ = tf; node_ = parent.lock(); name_ = name; costmap_ = costmap_ros->getCostmap(); global_frame_ = costmap_ros->getGlobalFrameID(); //参数初始化 nav2_util::declare_parameter_if_not_declared( node_, name_, + ".interpolation_resolution", rclcpp::ParameterValue(0.1)); node_->get_parameter(name_ + ".interpolation_resolution", interpolation_resolution_); } void CustomPlanner::cleanup() { RCLCPP_INFO(node_->get_logger(), "正在清理类型为CustomPlanner的插件 %s", name_.c_str()); } void CustomPlanner::activate() { RCLCPP_INFO(node_->get_logger(), "正在激活类型为CustomPlanner的插件 %s", name_.c_str()); } void CustomPlanner::deactivate() { RCLCPP_INFO(node_->get_logger(), "正在停用类型为CustomPlanner的插件 %s", name_.c_str()); } nav_msgs::msg::Path CustomPlanner::createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal) { nav_msgs::msg::Path global_path; //进行规划 return global_path; } } // namespace nav2_custom_planner #include "pluginlib/class_list_macros.hpp" PLUGINLIB_EXPORT_CLASS(nav2_custom_planner::CustomPlanner, nav2_core::GlobalPlanner);
nav2_custom_planner.hpp代码:
#ifndef NAV2_CUSTOM_PLANNER__NAV2_CUSTOM_PLANNER_HPP_ #define NAV2_CUSTOM_PLANNER__NAV2_CUSTOM_PLANNER_HPP_ #include <memory> #include <string> #include "geometry_msgs/msg/point.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "rclcpp/rclcpp.hpp" #include "nav2_core/global_planner.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_util/lifecycle_node.hpp" #include "nav2_util/robot_utils.hpp" #include "nav_msgs/msg/path.hpp" namespace nav2_custom_planner { //自定义导航规划器类 class CustomPlanner : public nav2_core::GlobalPlanner{ public: CustomPlanner() = default; ~CustomPlanner() = default; //插件配置方法 void configure( const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr<tf2_ros::Buffer> tf, std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override; //插件清理的方法 void cleanup() override; //插件激活的方法 void activate() override; //插件停用的方法 void deactivate() override; //为给定的起始和目标位姿创建路径的方法 nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal) override; private: //坐标变换缓存指针,可用于查询坐标关系 std::shared_ptr<tf2_ros::Buffer> tf_; //节点指针 nav2_util::LifecycleNode::SharedPtr node_; //全局代价地图 nav2_costmap_2d::Costmap2D *costmap_; //全局代价地图的坐标系 std::string global_frame_, name_; //插值分辨率 double interpolation_resolution_; }; } // namespace nav2_custom_planner #endif // NAV2_CUSTOM_PLANNER__NAV2_CUSTOM_PLANNER_HPP_
-
@43996173 空间构建错误:
tingbo@DESKTOP-NHH5E05:~/chapt8/chapt8_ws$ colcon build Starting >>> autopatrol_interfaces Starting >>> autopatrol_robot Starting >>> fishbot_application Starting >>> fishbot_description Starting >>> fishbot_navigation2 Starting >>> nav2_custom_planner Finished <<< fishbot_description [2.74s] Finished <<< fishbot_navigation2 [2.75s] Finished <<< autopatrol_interfaces [5.11s] Finished <<< fishbot_application [8.58s] Finished <<< autopatrol_robot [8.63s] --- stderr: nav2_custom_planner /home/tingbo/chapt8/chapt8_ws/src/nav2_custom_planner/src/nav2_custom_planner.cpp: In member function ‘virtual void nav2_custom_planner::CustomPlanner::configure(const WeakPtr&, std::string, std::shared_ptr<tf2_ros::Buffer>, std::shared_ptr<nav2_costmap_2d::Costmap2DROS>)’: /home/tingbo/chapt8/chapt8_ws/src/nav2_custom_planner/src/nav2_custom_planner.cpp:19:57: error: no matching function for call to ‘declare_parameter_if_not_declared(rclcpp_lifecycle::LifecycleNode::SharedPtr&, std::string&, const char*, rclcpp::ParameterValue)’ 19 | nav2_util::declare_parameter_if_not_declared( | ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^ 20 | node_, name_, + ".interpolation_resolution", | ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ 21 | rclcpp::ParameterValue(0.1)); | ~~~~~~~~~~~~~~~~~~~~~~~~~~~~ In file included from /home/tingbo/chapt8/chapt8_ws/src/nav2_custom_planner/src/nav2_custom_planner.cpp:1: /opt/ros/humble/include/nav2_util/node_utils.hpp:92:6: note: candidate: ‘template<class NodeT> void nav2_util::declare_parameter_if_not_declared(NodeT, const string&, const rclcpp::ParameterValue&, const ParameterDescriptor&)’ 92 | void declare_parameter_if_not_declared( | ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ /opt/ros/humble/include/nav2_util/node_utils.hpp:92:6: note: template argument deduction/substitution failed: /home/tingbo/chapt8/chapt8_ws/src/nav2_custom_planner/src/nav2_custom_planner.cpp:20:31: note: cannot convert ‘+(const char*)".interpolation_resolution"’ (type ‘const char*’) to type ‘const rclcpp::ParameterValue&’ 20 | node_, name_, + ".interpolation_resolution", | ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~ In file included from /home/tingbo/chapt8/chapt8_ws/src/nav2_custom_planner/src/nav2_custom_planner.cpp:1: /opt/ros/humble/include/nav2_util/node_utils.hpp:113:6: note: candidate: ‘template<class NodeT> void nav2_util::declare_parameter_if_not_declared(NodeT, const string&, const rclcpp::ParameterType&, const ParameterDescriptor&)’ 113 | void declare_parameter_if_not_declared( | ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ /opt/ros/humble/include/nav2_util/node_utils.hpp:113:6: note: template argument deduction/substitution failed: /home/tingbo/chapt8/chapt8_ws/src/nav2_custom_planner/src/nav2_custom_planner.cpp:20:31: note: cannot convert ‘+(const char*)".interpolation_resolution"’ (type ‘const char*’) to type ‘const rclcpp::ParameterType&’ 20 | node_, name_, + ".interpolation_resolution", | ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~ /home/tingbo/chapt8/chapt8_ws/src/nav2_custom_planner/src/nav2_custom_planner.cpp: In member function ‘virtual nav_msgs::msg::Path nav2_custom_planner::CustomPlanner::createPlan(const PoseStamped&, const PoseStamped&)’: /home/tingbo/chapt8/chapt8_ws/src/nav2_custom_planner/src/nav2_custom_planner.cpp:40:70: warning: unused parameter ‘start’ [-Wunused-parameter] 40 | CustomPlanner::createPlan(const geometry_msgs::msg::PoseStamped &start, | ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~~~~ /home/tingbo/chapt8/chapt8_ws/src/nav2_custom_planner/src/nav2_custom_planner.cpp:41:63: warning: unused parameter ‘goal’ [-Wunused-parameter] 41 | const geometry_msgs::msg::PoseStamped &goal) { | ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~~~ gmake[2]: *** [CMakeFiles/nav2_custom_planner_Plugin.dir/build.make:76:CMakeFiles/nav2_custom_planner_Plugin.dir/src/nav2_custom_planner.cpp.o] 错误 1 gmake[1]: *** [CMakeFiles/Makefile2:137:CMakeFiles/nav2_custom_planner_Plugin.dir/all] 错误 2 gmake: *** [Makefile:146:all] 错误 2 --- Failed <<< nav2_custom_planner [25.2s, exited with code 2] Summary: 5 packages finished [31.0s] 1 package failed: nav2_custom_planner 1 package had stderr output: nav2_custom_planner