Skip to content

Commit

Permalink
Add files via upload
Browse files Browse the repository at this point in the history
  • Loading branch information
yiyunevin authored Sep 11, 2022
1 parent d43c06d commit e666608
Show file tree
Hide file tree
Showing 17 changed files with 2,238 additions and 0 deletions.
74 changes: 74 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
cmake_minimum_required(VERSION 3.0.2)
project(rrt_planner)

# add_compile_options(-std=c++11)

find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
geometry_msgs
gazebo_msgs
nav_msgs
sensor_msgs
message_generation
)

# catkin_python_setup()

################################################
## Declare ROS messages, services and actions ##
################################################

add_service_files(
FILES
StartGoalPath.srv
OccMapInfo.srv
RandomGetPath.srv
MapOcc.srv
)

generate_messages( # 自定義 Serivice 中有用到的 ROS library
DEPENDENCIES
geometry_msgs
)

###################################
## catkin specific configuration ##
###################################

catkin_package(
INCLUDE_DIRS include
LIBRARIES rrt_planner
CATKIN_DEPENDS
roscpp
rospy
geometry_msgs
gazebo_msgs
nav_msgs
message_runtime
# DEPENDS system_lib
)

###########
## Build ##
###########

include_directories(
include
${catkin_INCLUDE_DIRS}
)

add_executable(rrt_planner
src/rrt_planner.cpp
src/grid_map.cpp
)
target_link_libraries(rrt_planner ${catkin_LIBRARIES} )

#############
## Install ##
#############


#############
## Testing ##
#############
14 changes: 14 additions & 0 deletions config/base_global_planner_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
BRRTStarPlanner:
tolerance: 0.5
radius: 0.1
epsilon_min: 0.01
epsilon_max: 0.1
max_node_num: 10000
# waypoint_step: 0.025
robot_radius: 0.1 # 0.45 #0.29 # obstacle collision
inter_radius: -1.0
timeout_second: 20.0
global_visualization: true
global_debug: true
map_debug: false
visualization_step: 1
169 changes: 169 additions & 0 deletions config/global_test.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,169 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
Splitter Ratio: 0.5
Tree Height: 549
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 0.4000000059604645
Class: rviz/Map
Color Scheme: map
Draw Behind: false
Enabled: true
Name: Map
Topic: /map
Unreliable: false
Use Timestamp: false
Value: true
- Class: rviz/Marker
Enabled: true
Marker Topic: /rrt_planner/marker_tree
Name: MK_Tree
Namespaces:
{}
Queue Size: 100
Value: true
- Class: rviz/Marker
Enabled: false
Marker Topic: /rrt_planner/marker_path
Name: MK_Path
Namespaces:
{}
Queue Size: 1
Value: false
- Class: rviz/Marker
Enabled: true
Marker Topic: /marker_start
Name: MK_start
Namespaces:
{}
Queue Size: 1
Value: true
- Class: rviz/Marker
Enabled: true
Marker Topic: /marker_goal
Name: MK_goal
Namespaces:
{}
Queue Size: 1
Value: true
- Class: rviz/Marker
Enabled: true
Marker Topic: /rrt_planner/marker_beacon
Name: MK_beacons
Namespaces:
{}
Queue Size: 1
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: map
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 6.996328353881836
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Field of View: 1.5707963705062866
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 1.5697963237762451
Target Frame: <Fixed Frame>
Yaw: 3.140000104904175
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: true
QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004f30000003efc0100000002fb0000000800540069006d00650100000000000004f3000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000397000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1267
X: 632
Y: 123
66 changes: 66 additions & 0 deletions include/rrt_planner/grid_map.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
#ifndef RRT_GRID_MAP_H_
#define RRT_GRID_MAP_H_

#include<math.h>
#include<stdio.h>
#include<ros/ros.h>
#include<nav_msgs/OccupancyGrid.h>
#include<geometry_msgs/Point.h>
#include<geometry_msgs/Pose.h>
#include<geometry_msgs/PoseStamped.h>
#include<rrt_planner/node.h>

#define TWO_PI 2*M_PI
#define PIECE M_PI/10

class GridMap
{
public:

ros::NodeHandle nh_;
GridMap();
GridMap(double robot_radius, bool debug);
~GridMap();

void initialize(double robot_radius, bool debug);
void generate_start_goal(geometry_msgs::PoseStamped& start,
geometry_msgs::PoseStamped& goal,
int id);
void generate_goal( geometry_msgs::PoseStamped& start,
geometry_msgs::PoseStamped& goal,
int id);

void get_occ_map_info();
void get_map_info_value(double& m_origin_x, double& m_origin_y, double& m_res, int& m_width, int& m_height);
void getOrigin(geometry_msgs::Point& origin);
void getOrigin(double& x, double& y);
void getResolution(double& r);
void getMapSize(int& x, int& y);
int occGridValue(double x, double y);
std::string getMapFrame();
bool isObstaclePoint(double x, double y);
bool isObstacleBetween(double Ax, double Ay, double Bx, double By);
bool isObstacleAround(double x, double y, unsigned int step);

private:

void occMapCB(const nav_msgs::OccupancyGrid::ConstPtr& msg);
double getRandomValue(double min, double max);
bool rectangleFillCells(double max_x,
double max_y,
double min_x,
double min_y,
std::vector<geometry_msgs::Point>& polygon_cells);

bool debug_;
nav_msgs::OccupancyGrid occ_map_data_;
double resolution;
double originX;
double originY;
int width;
int height;
double robot_radius_;
ros::Subscriber occ_sub_;
};

#endif
49 changes: 49 additions & 0 deletions include/rrt_planner/node.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
#ifndef RRT_NODE_H_
#define RRT_NODE_H_

#include <cmath>

static inline double euclideanDistance2D(double x1, double y1, double x2, double y2)
{
return hypot( (x1-x2), (y1-y2) );
}

struct Node {
double x{0.0};
double y{0.0};
int node_id{0};
int parent_id{-1};
double cost{0.0};

Node() {}

Node(double px, double py, int node_index, int parent_index) :
x(px),
y(py),
node_id(node_index),
parent_id(parent_index) {}

bool operator ==(const Node& node)
{
if (node_id == node.node_id)
return true;

if ( euclideanDistance2D(this->x, this->y, node.x, node.y) <= 0.001 )
return true;

return false;
}

bool operator !=(const Node& node)
{
if (node_id == node.node_id)
return false;

if ( euclideanDistance2D(this->x, this->y, node.x, node.y) <= 0.001 )
return false;

return true;
}
};

#endif
Loading

0 comments on commit e666608

Please sign in to comment.