ROS(indigo)RRT路径规划
源码地址:https://github.com/nalin1096/path_planning
路径规划
使用ROS实现了基于RRT路径规划算法。
发行版 - indigo
算法在有一个障碍的环境找到优化的路径。算法可视化在RVIZ完成,代码是用C ++编写。
包有两个可执行文件:
1 ros_node
2 env_node
RVIZ参数:
1 Frame_id =“path_planner”
2 marker_topic =“path_planner_rrt”
说明:
- 打开终端,输入
- $ roscore
- 打开新的终端并转到catkin工作区:
- $ catkin_make
- $ source ./devel/setup.bash
- $ rosrun path_planning env_node
- 打开新的终端
- $ rosrun rviz rviz
- 在RVIZ窗口,更改:
- 在全局选项固定框架“path_planner”
- 添加标记和标记改变主题,以“path_planner_rrt”
- 打开新的终端
- $ rosrun path_planning rrt_node
如果想修改环境environment,如下:
#include <ros/ros.h>
#include <visualization_msgs/Marker.h>
#include <path_planning/rrt.h>
#include <path_planning/obstacles.h>
#include <geometry_msgs/Point.h> #include <iostream>
#include <cmath>
#include <math.h>
#include <stdlib.h>
#include <unistd.h>
#include <vector> using namespace rrt; void initializeMarkers(visualization_msgs::Marker &boundary,
visualization_msgs::Marker &obstacle)
{
//init headers
boundary.header.frame_id = obstacle.header.frame_id = "path_planner";
boundary.header.stamp = obstacle.header.stamp = ros::Time::now();
boundary.ns = obstacle.ns = "path_planner";
boundary.action = obstacle.action = visualization_msgs::Marker::ADD;
boundary.pose.orientation.w = obstacle.pose.orientation.w = 1.0; //setting id for each marker
boundary.id = 110;
obstacle.id = 111; //defining types
boundary.type = visualization_msgs::Marker::LINE_STRIP;
obstacle.type = visualization_msgs::Marker::LINE_LIST; //setting scale
boundary.scale.x = 1;
obstacle.scale.x = 0.2; //assigning colors
boundary.color.r = obstacle.color.r = 0.0f;
boundary.color.g = obstacle.color.g = 0.0f;
boundary.color.b = obstacle.color.b = 0.0f; boundary.color.a = obstacle.color.a = 1.0f;
} vector<geometry_msgs::Point> initializeBoundary()
{
vector<geometry_msgs::Point> bondArray; geometry_msgs::Point point; //first point
point.x = 0;
point.y = 0;
point.z = 0; bondArray.push_back(point); //second point
point.x = 0;
point.y = 100;
point.z = 0; bondArray.push_back(point); //third point
point.x = 100;
point.y = 100;
point.z = 0; bondArray.push_back(point); //fourth point
point.x = 100;
point.y = 0;
point.z = 0;
bondArray.push_back(point); //first point again to complete the box
point.x = 0;
point.y = 0;
point.z = 0;
bondArray.push_back(point); return bondArray;
} vector<geometry_msgs::Point> initializeObstacles()
{
vector< vector<geometry_msgs::Point> > obstArray; vector<geometry_msgs::Point> obstaclesMarker; obstacles obst; obstArray = obst.getObstacleArray(); for(int i=0; i<obstArray.size(); i++)
{
for(int j=1; j<5; j++)
{
obstaclesMarker.push_back(obstArray[i][j-1]);
obstaclesMarker.push_back(obstArray[i][j]);
} }
return obstaclesMarker;
} int main(int argc,char** argv)
{
//initializing ROS
ros::init(argc,argv,"env_node");
ros::NodeHandle n; //defining Publisher
ros::Publisher env_publisher = n.advertise<visualization_msgs::Marker>("path_planner_rrt",1); //defining markers
visualization_msgs::Marker boundary;
visualization_msgs::Marker obstacle; initializeMarkers(boundary, obstacle); //initializing rrtTree
RRT myRRT(2.0,2.0);
int goalX, goalY;
goalX = goalY = 95; boundary.points = initializeBoundary();
obstacle.points = initializeObstacles(); env_publisher.publish(boundary);
env_publisher.publish(obstacle); while(ros::ok())
{
env_publisher.publish(boundary);
env_publisher.publish(obstacle);
ros::spinOnce();
ros::Duration(1).sleep();
}
return 1;
}
障碍物obstacles,可修改调整障碍物个数等:
#include <path_planning/obstacles.h>
#include <geometry_msgs/Point.h> vector< vector<geometry_msgs::Point> > obstacles::getObstacleArray()
{
vector<geometry_msgs::Point> obstaclePoint;
geometry_msgs::Point point; //first point
point.x = 50;
point.y = 50;
point.z = 0; obstaclePoint.push_back(point); //second point
point.x = 50;
point.y = 70;
point.z = 0; obstaclePoint.push_back(point); //third point
point.x = 80;
point.y = 70;
point.z = 0; obstaclePoint.push_back(point); //fourth point
point.x = 80;
point.y = 50;
point.z = 0;
obstaclePoint.push_back(point); //first point again to complete the box
point.x = 50;
point.y = 50;
point.z = 0;
obstaclePoint.push_back(point); obstacleArray.push_back(obstaclePoint); return obstacleArray; }
RRT:
#include <path_planning/rrt.h>
#include <math.h>
#include <cstddef>
#include <iostream> using namespace rrt; /**
* default constructor for RRT class
* initializes source to 0,0
* adds sorce to rrtTree
*/
RRT::RRT()
{
RRT::rrtNode newNode;
newNode.posX = 0;
newNode.posY = 0;
newNode.parentID = 0;
newNode.nodeID = 0;
rrtTree.push_back(newNode);
} /**
* default constructor for RRT class
* initializes source to input X,Y
* adds sorce to rrtTree
*/
RRT::RRT(double input_PosX, double input_PosY)
{
RRT::rrtNode newNode;
newNode.posX = input_PosX;
newNode.posY = input_PosY;
newNode.parentID = 0;
newNode.nodeID = 0;
rrtTree.push_back(newNode);
} /**
* Returns the current RRT tree
* @return RRT Tree
*/
vector<RRT::rrtNode> RRT::getTree()
{
return rrtTree;
} /**
* For setting the rrtTree to the inputTree
* @param rrtTree
*/
void RRT::setTree(vector<RRT::rrtNode> input_rrtTree)
{
rrtTree = input_rrtTree;
} /**
* to get the number of nodes in the rrt Tree
* @return tree size
*/
int RRT::getTreeSize()
{
return rrtTree.size();
} /**
* adding a new node to the rrt Tree
*/
void RRT::addNewNode(RRT::rrtNode node)
{
rrtTree.push_back(node);
} /**
* removing a node from the RRT Tree
* @return the removed tree
*/
RRT::rrtNode RRT::removeNode(int id)
{
RRT::rrtNode tempNode = rrtTree[id];
rrtTree.erase(rrtTree.begin()+id);
return tempNode;
} /**
* getting a specific node
* @param node id for the required node
* @return node in the rrtNode structure
*/
RRT::rrtNode RRT::getNode(int id)
{
return rrtTree[id];
} /**
* return a node from the rrt tree nearest to the given point
* @param X position in X cordinate
* @param Y position in Y cordinate
* @return nodeID of the nearest Node
*/
int RRT::getNearestNodeID(double X, double Y)
{
int i, returnID;
double distance = 9999, tempDistance;
for(i=0; i<this->getTreeSize(); i++)
{
tempDistance = getEuclideanDistance(X,Y, getPosX(i),getPosY(i));
if (tempDistance < distance)
{
distance = tempDistance;
returnID = i;
}
}
return returnID;
} /**
* returns X coordinate of the given node
*/
double RRT::getPosX(int nodeID)
{
return rrtTree[nodeID].posX;
} /**
* returns Y coordinate of the given node
*/
double RRT::getPosY(int nodeID)
{
return rrtTree[nodeID].posY;
} /**
* set X coordinate of the given node
*/
void RRT::setPosX(int nodeID, double input_PosX)
{
rrtTree[nodeID].posX = input_PosX;
} /**
* set Y coordinate of the given node
*/
void RRT::setPosY(int nodeID, double input_PosY)
{
rrtTree[nodeID].posY = input_PosY;
} /**
* returns parentID of the given node
*/
RRT::rrtNode RRT::getParent(int id)
{
return rrtTree[rrtTree[id].parentID];
} /**
* set parentID of the given node
*/
void RRT::setParentID(int nodeID, int parentID)
{
rrtTree[nodeID].parentID = parentID;
} /**
* add a new childID to the children list of the given node
*/
void RRT::addChildID(int nodeID, int childID)
{
rrtTree[nodeID].children.push_back(childID);
} /**
* returns the children list of the given node
*/
vector<int> RRT::getChildren(int id)
{
return rrtTree[id].children;
} /**
* returns number of children of a given node
*/
int RRT::getChildrenSize(int nodeID)
{
return rrtTree[nodeID].children.size();
} /**
* returns euclidean distance between two set of X,Y coordinates
*/
double RRT::getEuclideanDistance(double sourceX, double sourceY, double destinationX, double destinationY)
{
return sqrt(pow(destinationX - sourceX,2) + pow(destinationY - sourceY,2));
} /**
* returns path from root to end node
* @param endNodeID of the end node
* @return path containing ID of member nodes in the vector form
*/
vector<int> RRT::getRootToEndPath(int endNodeID)
{
vector<int> path;
path.push_back(endNodeID);
while(rrtTree[path.front()].nodeID != 0)
{
//std::cout<<rrtTree[path.front()].nodeID<<endl;
path.insert(path.begin(),rrtTree[path.front()].parentID);
}
return path;
}
RRT节点:
#include <ros/ros.h>
#include <visualization_msgs/Marker.h>
#include <geometry_msgs/Point.h>
#include <path_planning/rrt.h>
#include <path_planning/obstacles.h>
#include <iostream>
#include <cmath>
#include <math.h>
#include <stdlib.h>
#include <unistd.h>
#include <vector>
#include <time.h> #define success false
#define running true using namespace rrt; bool status = running; void initializeMarkers(visualization_msgs::Marker &sourcePoint,
visualization_msgs::Marker &goalPoint,
visualization_msgs::Marker &randomPoint,
visualization_msgs::Marker &rrtTreeMarker,
visualization_msgs::Marker &finalPath)
{
//init headers
sourcePoint.header.frame_id = goalPoint.header.frame_id = randomPoint.header.frame_id = rrtTreeMarker.header.frame_id = finalPath.header.frame_id = "path_planner";
sourcePoint.header.stamp = goalPoint.header.stamp = randomPoint.header.stamp = rrtTreeMarker.header.stamp = finalPath.header.stamp = ros::Time::now();
sourcePoint.ns = goalPoint.ns = randomPoint.ns = rrtTreeMarker.ns = finalPath.ns = "path_planner";
sourcePoint.action = goalPoint.action = randomPoint.action = rrtTreeMarker.action = finalPath.action = visualization_msgs::Marker::ADD;
sourcePoint.pose.orientation.w = goalPoint.pose.orientation.w = randomPoint.pose.orientation.w = rrtTreeMarker.pose.orientation.w = finalPath.pose.orientation.w = 1.0; //setting id for each marker
sourcePoint.id = 0;
goalPoint.id = 1;
randomPoint.id = 2;
rrtTreeMarker.id = 3;
finalPath.id = 4; //defining types
rrtTreeMarker.type = visualization_msgs::Marker::LINE_LIST;
finalPath.type = visualization_msgs::Marker::LINE_STRIP;
sourcePoint.type = goalPoint.type = randomPoint.type = visualization_msgs::Marker::SPHERE; //setting scale
rrtTreeMarker.scale.x = 0.2;
finalPath.scale.x = 1;
sourcePoint.scale.x = goalPoint.scale.x = randomPoint.scale.x = 2;
sourcePoint.scale.y = goalPoint.scale.y = randomPoint.scale.y = 2;
sourcePoint.scale.z = goalPoint.scale.z = randomPoint.scale.z = 1; //assigning colors
sourcePoint.color.r = 1.0f;
goalPoint.color.g = 1.0f;
randomPoint.color.b = 1.0f; rrtTreeMarker.color.r = 0.8f;
rrtTreeMarker.color.g = 0.4f; finalPath.color.r = 0.2f;
finalPath.color.g = 0.2f;
finalPath.color.b = 1.0f; sourcePoint.color.a = goalPoint.color.a = randomPoint.color.a = rrtTreeMarker.color.a = finalPath.color.a = 1.0f;
} vector< vector<geometry_msgs::Point> > getObstacles()
{
obstacles obst;
return obst.getObstacleArray();
} void addBranchtoRRTTree(visualization_msgs::Marker &rrtTreeMarker, RRT::rrtNode &tempNode, RRT &myRRT)
{ geometry_msgs::Point point; point.x = tempNode.posX;
point.y = tempNode.posY;
point.z = 0;
rrtTreeMarker.points.push_back(point); RRT::rrtNode parentNode = myRRT.getParent(tempNode.nodeID); point.x = parentNode.posX;
point.y = parentNode.posY;
point.z = 0; rrtTreeMarker.points.push_back(point);
} bool checkIfInsideBoundary(RRT::rrtNode &tempNode)
{
if(tempNode.posX < 0 || tempNode.posY < 0 || tempNode.posX > 100 || tempNode.posY > 100 ) return false;
else return true;
} bool checkIfOutsideObstacles(vector< vector<geometry_msgs::Point> > &obstArray, RRT::rrtNode &tempNode)
{
double AB, AD, AMAB, AMAD; for(int i=0; i<obstArray.size(); i++)
{
AB = (pow(obstArray[i][0].x - obstArray[i][1].x,2) + pow(obstArray[i][0].y - obstArray[i][1].y,2));
AD = (pow(obstArray[i][0].x - obstArray[i][3].x,2) + pow(obstArray[i][0].y - obstArray[i][3].y,2));
AMAB = (((tempNode.posX - obstArray[i][0].x) * (obstArray[i][1].x - obstArray[i][0].x)) + (( tempNode.posY - obstArray[i][0].y) * (obstArray[i][1].y - obstArray[i][0].y)));
AMAD = (((tempNode.posX - obstArray[i][0].x) * (obstArray[i][3].x - obstArray[i][0].x)) + (( tempNode.posY - obstArray[i][0].y) * (obstArray[i][3].y - obstArray[i][0].y)));
//(0<AM⋅AB<AB⋅AB)∧(0<AM⋅AD<AD⋅AD)
if((0 < AMAB) && (AMAB < AB) && (0 < AMAD) && (AMAD < AD))
{
return false;
}
}
return true;
} void generateTempPoint(RRT::rrtNode &tempNode)
{
int x = rand() % 150 + 1;
int y = rand() % 150 + 1;
//std::cout<<"Random X: "<<x <<endl<<"Random Y: "<<y<<endl;
tempNode.posX = x;
tempNode.posY = y;
} bool addNewPointtoRRT(RRT &myRRT, RRT::rrtNode &tempNode, int rrtStepSize, vector< vector<geometry_msgs::Point> > &obstArray)
{
int nearestNodeID = myRRT.getNearestNodeID(tempNode.posX,tempNode.posY); RRT::rrtNode nearestNode = myRRT.getNode(nearestNodeID); double theta = atan2(tempNode.posY - nearestNode.posY,tempNode.posX - nearestNode.posX); tempNode.posX = nearestNode.posX + (rrtStepSize * cos(theta));
tempNode.posY = nearestNode.posY + (rrtStepSize * sin(theta)); if(checkIfInsideBoundary(tempNode) && checkIfOutsideObstacles(obstArray,tempNode))
{
tempNode.parentID = nearestNodeID;
tempNode.nodeID = myRRT.getTreeSize();
myRRT.addNewNode(tempNode);
return true;
}
else
return false;
} bool checkNodetoGoal(int X, int Y, RRT::rrtNode &tempNode)
{
double distance = sqrt(pow(X-tempNode.posX,2)+pow(Y-tempNode.posY,2));
if(distance < 3)
{
return true;
}
return false;
} void setFinalPathData(vector< vector<int> > &rrtPaths, RRT &myRRT, int i, visualization_msgs::Marker &finalpath, int goalX, int goalY)
{
RRT::rrtNode tempNode;
geometry_msgs::Point point;
for(int j=0; j<rrtPaths[i].size();j++)
{
tempNode = myRRT.getNode(rrtPaths[i][j]); point.x = tempNode.posX;
point.y = tempNode.posY;
point.z = 0; finalpath.points.push_back(point);
} point.x = goalX;
point.y = goalY;
finalpath.points.push_back(point);
} int main(int argc,char** argv)
{
//initializing ROS
ros::init(argc,argv,"rrt_node");
ros::NodeHandle n; //defining Publisher
ros::Publisher rrt_publisher = n.advertise<visualization_msgs::Marker>("path_planner_rrt",1); //defining markers
visualization_msgs::Marker sourcePoint;
visualization_msgs::Marker goalPoint;
visualization_msgs::Marker randomPoint;
visualization_msgs::Marker rrtTreeMarker;
visualization_msgs::Marker finalPath; initializeMarkers(sourcePoint, goalPoint, randomPoint, rrtTreeMarker, finalPath); //setting source and goal
sourcePoint.pose.position.x = 2;
sourcePoint.pose.position.y = 2; goalPoint.pose.position.x = 95;
goalPoint.pose.position.y = 95; rrt_publisher.publish(sourcePoint);
rrt_publisher.publish(goalPoint);
ros::spinOnce();
ros::Duration(0.01).sleep(); srand (time(NULL));
//initialize rrt specific variables //initializing rrtTree
RRT myRRT(2.0,2.0);
int goalX, goalY;
goalX = goalY = 95; int rrtStepSize = 3; vector< vector<int> > rrtPaths;
vector<int> path;
int rrtPathLimit = 1; int shortestPathLength = 9999;
int shortestPath = -1; RRT::rrtNode tempNode; vector< vector<geometry_msgs::Point> > obstacleList = getObstacles(); bool addNodeResult = false, nodeToGoal = false; while(ros::ok() && status)
{
if(rrtPaths.size() < rrtPathLimit)
{
generateTempPoint(tempNode);
//std::cout<<"tempnode generated"<<endl;
addNodeResult = addNewPointtoRRT(myRRT,tempNode,rrtStepSize,obstacleList);
if(addNodeResult)
{
// std::cout<<"tempnode accepted"<<endl;
addBranchtoRRTTree(rrtTreeMarker,tempNode,myRRT);
// std::cout<<"tempnode printed"<<endl;
nodeToGoal = checkNodetoGoal(goalX, goalY,tempNode);
if(nodeToGoal)
{
path = myRRT.getRootToEndPath(tempNode.nodeID);
rrtPaths.push_back(path);
std::cout<<"New Path Found. Total paths "<<rrtPaths.size()<<endl;
//ros::Duration(10).sleep();
//std::cout<<"got Root Path"<<endl;
}
}
}
else //if(rrtPaths.size() >= rrtPathLimit)
{
status = success;
std::cout<<"Finding Optimal Path"<<endl;
for(int i=0; i<rrtPaths.size();i++)
{
if(rrtPaths[i].size() < shortestPath)
{
shortestPath = i;
shortestPathLength = rrtPaths[i].size();
}
}
setFinalPathData(rrtPaths, myRRT, shortestPath, finalPath, goalX, goalY);
rrt_publisher.publish(finalPath);
} rrt_publisher.publish(sourcePoint);
rrt_publisher.publish(goalPoint);
rrt_publisher.publish(rrtTreeMarker);
//rrt_publisher.publish(finalPath);
ros::spinOnce();
ros::Duration(0.01).sleep();
}
return 1;
}
头文件定义类如下:
obstacles:
#ifndef OBSTACLES_H
#define OBSTACLES_H
#include <geometry_msgs/Point.h>
#include <vector>
#include <iostream> using namespace std; class obstacles
{
public:
/** Default constructor */
obstacles() {}
/** Default destructor */
virtual ~obstacles() {} vector< vector<geometry_msgs::Point> > getObstacleArray(); protected:
private:
vector< vector<geometry_msgs::Point> > obstacleArray;
}; #endif // OBSTACLES_H
rrt:
#ifndef rrt_h
#define rrt_h #include <vector>
using namespace std;
namespace rrt {
class RRT{ public: RRT();
RRT(double input_PosX, double input_PosY); struct rrtNode{
int nodeID;
double posX;
double posY;
int parentID;
vector<int> children;
}; vector<rrtNode> getTree();
void setTree(vector<rrtNode> input_rrtTree);
int getTreeSize(); void addNewNode(rrtNode node);
rrtNode removeNode(int nodeID);
rrtNode getNode(int nodeID); double getPosX(int nodeID);
double getPosY(int nodeID);
void setPosX(int nodeID, double input_PosX);
void setPosY(int nodeID, double input_PosY); rrtNode getParent(int nodeID);
void setParentID(int nodeID, int parentID); void addChildID(int nodeID, int childID);
vector<int> getChildren(int nodeID);
int getChildrenSize(int nodeID); int getNearestNodeID(double X, double Y);
vector<int> getRootToEndPath(int endNodeID); private:
vector<rrtNode> rrtTree;
double getEuclideanDistance(double sourceX, double sourceY, double destinationX, double destinationY);
};
}; #endif
其他代码:
CMakeLists:
cmake_minimum_required(VERSION 2.8.3)
project(path_planning) ## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
visualization_msgs
) ## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system) ## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup() ################################################
## Declare ROS messages, services and actions ##
################################################ ## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependencies might have been
## pulled in transitively but can be declared for certainty nonetheless:
## * add a build_depend tag for "message_generation"
## * add a run_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) ## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# ) ## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# ) ## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# ) ## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# std_msgs# visualization_msgs
# ) ###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if you package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include
LIBRARIES path_planning
CATKIN_DEPENDS roscpp std_msgs visualization_msgs
DEPENDS system_lib
) ###########
## Build ##
########### ## Specify additional locations of header files
## Your package locations should be listed before other locations
# include_directories(include)
include_directories(include
${catkin_INCLUDE_DIRS}
) ## Declare a cpp library
add_library(path_planning
src/rrt.cpp
src/obstacles.cpp
) ## Declare a cpp executable
# add_executable(path_planning_node src/path_planning_node.cpp) add_executable(rrt_node src/rrt_node.cpp)
add_dependencies(rrt_node path_planning)
target_link_libraries(rrt_node path_planning ${catkin_LIBRARIES} ) add_executable(env_node src/environment.cpp)
add_dependencies(env_node path_planning)
target_link_libraries(env_node path_planning ${catkin_LIBRARIES} ) ## Add cmake target dependencies of the executable/library
## as an example, message headers may need to be generated before nodes
# add_dependencies(path_planning_node path_planning_generate_messages_cpp) ## Specify libraries to link a library or executable target against
# target_link_libraries(path_planning_node
# ${catkin_LIBRARIES}
# ) #############
## Install ##
############# # all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html ## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# ) ## Mark executables and/or libraries for installation
# install(TARGETS path_planning path_planning_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# ) ## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# ) ## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# ) #############
## Testing ##
############# ## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_path_planning.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif() ## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
package:
<?xml version="1.0"?>
<package>
<name>path_planning</name>
<version>1.0.0</version>
<description>A path planning algorithm using RRT visualized in RVIZ</description> <!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="nalin00796@gmail.com">Nalin Gupta</maintainer> <!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license> <!-- Url tags are optional, but mutiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/path_planning</url> --> <!-- Author tags are optional, mutiple are allowed, one per tag -->
<!-- Authors do not have to be maintianers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> --> <!-- The *_depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use run_depend for packages you need at runtime: -->
<!-- <run_depend>message_runtime</run_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>visualization_msgs</build_depend>
<run_depend>roscpp</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>visualization_msgs</run_depend> <!-- The export tag contains other, unspecified, tags -->
<export>
<!-- You can specify that this package is a metapackage here: -->
<!-- <metapackage/> --> <!-- Other tools can request additional information be placed here --> </export>
</package>
ROS(indigo)RRT路径规划的更多相关文章
- RRT路径规划算法
传统的路径规划算法有人工势场法.模糊规则法.遗传算法.神经网络.模拟退火算法.蚁群优化算法等.但这些方法都需要在一个确定的空间内对障碍物进行建模,计算复杂度与机器人自由度呈指数关系,不适合解决多自由度 ...
- RRT路径规划算法(matlab实现)
基于快速扩展随机树(RRT / rapidly exploring random tree)的路径规划算法,通过对状态空间中的采样点进行碰撞检测,避免了对空间的建模,能够有效地解决高维空间和复杂约束的 ...
- ROS探索总结(十四)——move_base(路径规划)
在上一篇的博客中,我们一起学习了ROS定位于导航的总体框架,这一篇我们主要研究其中最重要的move_base包. 在总体框架图中可以看到,move_base提供了ROS导航的配置.运行.交互接口,它主 ...
- ROS源码解读(二)--全局路径规划
博客转载自:https://blog.csdn.net/xmy306538517/article/details/79032324 ROS中,机器人全局路径规划默认使用的是navfn包 ,move_b ...
- ROS源码解读(一)--局部路径规划
博客转载自:https://blog.csdn.net/xmy306538517/article/details/78772066 ROS局部路径导航包括Trajectory Rollout 和 Dy ...
- ros局部路径规划-DWA学习
ROS的路径规划器分为全局路径和局部路径规划,其中局部路径规划器使用的最广的为dwa,个人理解为: 首先全局路径规划会生成一条大致的全局路径,局部路径规划器会把全局路径给分段,然后根据分段的全局路径的 ...
- ROS机器人路径规划介绍--全局规划
ROS机器人路径规划算法主要包括2个部分:1)全局路径规划算法:2)局部路径规划算法: 一.全局路径规划 global planner ROS 的navigation官方功能包提供了三种全局路径规划器 ...
- 【2018.04.19 ROS机器人操作系统】机器人控制:运动规划、路径规划及轨迹规划简介之一
参考资料及致谢 本文的绝大部分内容转载自以下几篇文章,首先向原作者致谢,希望自己能在这些前辈们的基础上能有所总结提升. 1. 运动规划/路径规划/轨迹规划的联系与区别 https://blog.csd ...
- octomap中3d-rrt路径规划
路径规划 碰撞冲突检测 在octomap中制定起止点,目标点,使用rrt规划一条路径出来,没有运动学,动力学的限制,只要能避开障碍物. 效果如下: #include "ros/ros.h&q ...
随机推荐
- Java 接口基础详解
目录 Java接口示例 实现一个接口 接口实例 实现多个接口 方法签名重叠 接口变量 接口方法 接口默认方法 接口与继承 继承与默认方法 接口与多态性 在Java中,接口是一个抽象类型,有点类似于类, ...
- .Net Core 学习之路-AutoFac的使用
本文不介绍IoC和DI的概念,如果你对Ioc之前没有了解的话,建议先去搜索一下相关的资料 这篇文章将简单介绍一下AutoFac的基本使用以及在asp .net core中的应用 Autofac介绍 组 ...
- 0307-关于html
html最主要的三点: 1.标签的写法.用法 <标签名 属性名1="属性值1" 属性名2="属性值2">内容</标签名> 比如:< ...
- promise 的基本概念 和如何解决js中的异步编程问题 对 promis 的 then all ctch 的分析 和 await async 的理解
* promise承诺 * 解决js中异步编程的问题 * * 异步-同步 * 阻塞-无阻塞 * * 同步和异步的区别? 异步;同步 指的是被请求者 解析:被请求者(该事情的处理者)在处理完事情的时候的 ...
- Spring Cloud Eureka 自我保护机制
Eureka Server 在运行期间会去统计心跳失败比例在 15 分钟之内是否低于 85%,如果低于 85%,Eureka Server 会将这些实例保护起来,让这些实例不会过期,但是在保护期内如果 ...
- NIO-学习
通道(Channel) 通道表示打开到 IO 设备(例如:文件.套接字)的连接.若需要使用 NIO 系统,需要获取用于连接 IO 设备的通道以及用于容纳数据的缓冲区.然后操作缓冲区,对数据进行处理.C ...
- [JSOI 2011]分特产
Description JYY 带队参加了若干场ACM/ICPC 比赛,带回了许多土特产,要分给实验室的同学们. JYY 想知道,把这些特产分给N 个同学,一共有多少种不同的分法?当然,JYY 不希望 ...
- Educational Codeforces Round 19
A. k-Factorization 题目大意:给一个数n,求k个大于1的数,乘积为n.(n<=100,000,k<=20) 思路:分解质因数呗 #include<cstdio> ...
- 习题 7-3 uva211
题意:给你28个多米勒牌,要求刚好铺满一个7x8的图,输出所有答 案.每个牌只能使用一次 思路: 对每个位置分别搜索其右边 和 下边. 但是在中途,细节上有点问题.最开始想的是搜到最后一个点输出答案, ...
- hdu3966 点权模板-树链部分
Aragorn's Story Time Limit: 10000/3000 MS (Java/Others) Memory Limit: 32768/32768 K (Java/Others) ...