在线时间:8:00-16:00
迪恩网络APP
随时随地掌握行业动态
扫描二维码
关注迪恩网络微信公众号
开源软件名称(OpenSource Name):sikang/motion_primitive_library开源软件地址(OpenSource Url):https://github.com/sikang/motion_primitive_library开源编程语言(OpenSource Language):C++ 97.4%开源软件介绍(OpenSource Introduction):MRSL Motion Primitive Library for quadrotor v1.2Motion Primitive Library is a search-based planner to compute dynamically feasible trajectories for a quadrotor flying in an obstacle-cluttered environment. Our approach searches for smooth, minimum-time trajectories by exploring the map using a set of short-duration motion primitives. The primitives are generated by solving an optimal control problem and induce a finite lattice discretization on the state space which can be explored using a graph-search algorithm. The proposed approach is able to generate resolution-complete (i.e., optimal in the discretized space), safe, dynamically feasibility trajectories efficiently by exploiting the explicit solution of a Linear Quadratic Minimum Time problem. It does not assume a hovering initial condition and, hence, is suitable for fast online re-planning while the robot is moving. More details about the algorithm can be found in following publications:
New Features in v1.2
New Features in v1.1
InstallationPrerequisite:
or simply run following commands: $ sudo apt-get update
$ sudo apt install -y libeigen3-dev libyaml-cpp-dev libproj-dev libopencv-dev cmake A) Simple cmakemkdir build && cd build && cmake .. && make -j4 B) Using Catkin (not recognizable by catkin_make)$ mv motion_primitive_library ~/catkin_ws/src
$ cd ~/catkin_ws & catkin_make_isolated -DCMAKE_BUILD_TYPE=Release CTestRun following command in the $ make test If everything works, you should see the results as: Total Test time (real) = 4.22 sec
Running tests...
Test project /home/sikang/thesis_ws/src/packages/mpl_ros/motion_primitive_library/build
Start 1: test_traj_solver
1/6 Test #1: test_traj_solver ........................ Passed 0.00 sec
Start 2: test_planner_2d
2/6 Test #2: test_planner_2d ......................... Passed 0.92 sec
Start 3: test_planner_2d_prior_traj
3/6 Test #3: test_planner_2d_prior_traj .............. Passed 0.93 sec
Start 4: test_planner_2d_with_yaw
4/6 Test #4: test_planner_2d_with_yaw ................ Passed 0.96 sec
Start 5: test_distance_map_planner_2d
5/6 Test #5: test_distance_map_planner_2d ............ Passed 1.33 sec
Start 6: test_distance_map_planner_2d_with_yaw
6/6 Test #6: test_distance_map_planner_2d_with_yaw ... Passed 2.39 sec
100% tests passed, 0 tests failed out of 6
Total Test time (real) = 6.54 sec Include in other projects:To link this lib properly, add following in the
Example UsagePreparationTo run the planner, three components are required to be set properly: 1) Set Start and Goal:We use the Waypoint2D start, goal; // Initialize start and goal as Waypoint2D
start.pos = Vec3f(2.5, -3.5);
start.use_pos = true;
start.use_vel = true;
start.use_acc = false;
start.use_jrk = false;
start.use_yaw = false;
goal.pos = Vec3f(35, 2.5);
goal.control = start.control; The flag
In equal, one can also set the attribute
2) Set collision checking method:Any planner needs a collision checking function, there are several utils in this package to checking collision for obstacles in different representations.
In the most common environment where obstacles are represented as voxels, we use std::shared_ptr<MPL::OccMapUtil> map_util; // Declare as a shared pointer
map_util.reset(new MPL::OccMapUtil); // Initialize map_util
map_util->setMap(origin, dim, data, resolution); // Set the map information
...
planner->setMapUtil(map_util); // Set collision checking util Here 3) Set control input:Our planner takes control input to generate primitives. User need to specify it before start planning.
An example for the control input decimal_t u_max = 0.5;
vec_E<VecDf> U;
const decimal_t du = u_max / num;
for(decimal_t dx = -u_max; dx <= u_max; dx += du )
for(decimal_t dy = -u_max; dy <= u_max; dy += du )
U.push_back(Vec2f(dx, dy));
...
planner->setU(U); // Set control input Run the planner:After setting up above 3 required components, a plan thread can be launched as: std::unique_ptr<MPL::OccMapPlanner> planner(new MPL::OccMapPlanner(true)); // Declare a 2D planner with verbose
planner->setMapUtil(map_util); // Set collision checking util
planner->setU(U); // Set control input
planner->setDt(1.0); // Set dt for each primitive
bool valid = planner->plan(start, goal); // Plan from start to goal Test ExamplesExample1 (direct plan):After compiling by $ ./build/test_planner_2d ./data/corridor.yaml You should see following messages if it works properly:
The output image is saved in the current folder: (blue dots show the expended states, blue and cyan circles indicate start and goal). Example2 (plan with a prior trajectory):Run following command for test a 2D planning, it first finds a trajector in low dimensional space (acceleration-driven), then it uses the planned trajectory to refine for a trajectory in high dimensional space (jerk-driven): $ ./build/test_planner_2d_prior_traj ./data/corridor.yaml In the following output image, the black curve is the prior trajectory: Example3 (plan with yaw constraint):In some cases, the robot needs to move forward within the FOV of the camera or
range sensor such that the yaw needs to be considered when planning. $ ./build/test_planner_2d_with_yaw ./data/corridor.yaml Example4 (perturb trajectory with potential field):In practical case, the robot wants to stay away from obstacles even though the nominal trajectory is collision free. To add a soft constraint based on the distance towards obstacles, one technique is to use the artificial potential field (APF). In this examplem, we show how to perturb a nominal trajectory based on the search-based method with APFs: $ ./build/test_distance_map_planner_2d ./data/corridor.yaml In addition, to do the perturbation iteratively, run the other node: $ ./build/test_distance_map_planner_2d_iterative ./data/corridor.yaml Example5 (perturb trajectory with potential field and yaw constraint):In a more comprehensive case, when the robot has limited FOV and sensing range, plan the trajectory that considers safety and yaw constraint: $ ./build/test_distance_map_planner_2d_with_yaw ./data/corridor.yaml Example6 (trajectory generation):This example illustrate the $ ./build/test_traj_solver Here we generate three different trajectories using the same path and time allocation: the red one is minimum velocity trajectory, the green one is the minimum acceleration trajectory and the blue one is the minimum jerk trajectory. DoxygenFor API, please refer to Doxygen. ROS WrapperThe interface with ROS for visualization and implementation can be found in |
2023-10-27
2022-08-15
2022-08-17
2022-09-23
2022-08-13
请发表评论