add advanced

This commit is contained in:
Robot 2024-10-31 16:15:02 +08:00
parent 25db4cef52
commit 9c28619442
4 changed files with 62 additions and 0 deletions

View File

@ -0,0 +1,31 @@
#include "my_planner.h"
#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS( my_planner::MyPlanner, nav_core::BaseLocalPlanner)
namespace my_planner
{
MyPlanner::MyPlanner()
{
setlocale(LC_ALL,"");
}
MyPlanner::~MyPlanner()
{}
void MyPlanner::initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros)
{
ROS_WARN("该我上场表演了!");
}
bool MyPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped>& plan)
{
return true;
}
bool MyPlanner::computeVelocityCommands(geometry_msgs::Twist& cmd_vel)
{
return true;
}
bool MyPlanner::isGoalReached()
{
return false;
}
} // namespace my_planner

View File

@ -0,0 +1,22 @@
#ifndef MY_PLANNER_H_
#define MY_PLANNER_H_
#include <ros/ros.h>
#include <nav_core/base_local_planner.h>
namespace my_planner
{
class MyPlanner : public nav_core::BaseLocalPlanner
{
public:
MyPlanner();
~MyPlanner();
void initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros);
bool setPlan(const std::vector<geometry_msgs::PoseStamped>& plan);
bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
bool isGoalReached();
};
} // namespace my_planner
#endif // MY_PLANNER_H_

View File

@ -0,0 +1,7 @@
<library path="lib/libmy_planner">
<class name="my_planner/MyPlanner" type="my_planner::MyPlanner" base_class_type="nav_core::BaseLocalPlanner">
<description>
老子的规划器
</description>
</class>
</library>

2
advanced/multi_agent/.gitignore vendored Normal file
View File

@ -0,0 +1,2 @@
# Ignore everything in this directory
*.bak