From 1c22042c7ba8c336bcf208d76fe304f857429870 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E8=B5=B5=E5=A2=9E=E5=90=9B?= <32793431+Junking1@users.noreply.github.com> Date: Fri, 7 May 2021 09:31:52 +0800 Subject: [PATCH 1/5] Update README.md --- README.md | 35 ++++++++++++++++++++++++++++++++++- 1 file changed, 34 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 10a985b16..2edbc66f6 100644 --- a/README.md +++ b/README.md @@ -49,12 +49,45 @@ Please kindly star :star: this project if it helps you. We take great efforts to * [Updates](#6-updates) + +# Quick start with ubuntu 20.04 +if Ubuntu 20.04,you should install nplot with the source code +``` +git clone https://github.com/stevengj/nlopt.git +cd nlopt +mkdir build +cd build +cmake .. +make +sudo make install +``` +after that,you can test the fast-planner,run the following commands to setup +``` + sudo apt-get install libarmadillo-dev + cd ${YOUR_WORKSPACE_PATH}/src + git clone https://github.com/HKUST-Aerial-Robotics/Fast-Planner.git + cd ../ + catkin_make +``` +You may check the detailed [instruction](#3-setup-and-config) to setup the project. +After compilation you can start the visualization by: + +``` + source devel/setup.bash && roslaunch plan_manage rviz.launch +``` +and start a simulation (run in a new terminals): +``` + source devel/setup.bash && roslaunch plan_manage kino_replan.launch +``` +You will find the random map and the drone in ```Rviz```. You can select goals for the drone to reach using the ```2D Nav Goal``` tool. A sample simulation is showed [here](#demo1). + + ## 1. Quick Start The project has been tested on Ubuntu 16.04(ROS Kinetic) and 18.04(ROS Melodic). Take Ubuntu 18.04 as an example, run the following commands to setup: ``` - sudo apt-get install libarmadillo-dev ros-melodic-nlopt + sudo apt-get install libarmadillo-dev cd ${YOUR_WORKSPACE_PATH}/src git clone https://github.com/HKUST-Aerial-Robotics/Fast-Planner.git cd ../ From 728781647445bba840a83f515ac83c33c426acd1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E8=B5=B5=E5=A2=9E=E5=90=9B?= <32793431+Junking1@users.noreply.github.com> Date: Fri, 7 May 2021 09:35:22 +0800 Subject: [PATCH 2/5] Update odom_visualization.cpp --- .../src/odom_visualization.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/uav_simulator/Utils/odom_visualization/src/odom_visualization.cpp b/uav_simulator/Utils/odom_visualization/src/odom_visualization.cpp index 69b998228..77dafee52 100755 --- a/uav_simulator/Utils/odom_visualization/src/odom_visualization.cpp +++ b/uav_simulator/Utils/odom_visualization/src/odom_visualization.cpp @@ -81,7 +81,7 @@ void odom_callback(const nav_msgs::Odometry::ConstPtr& msg) // Pose poseROS.header = msg->header; poseROS.header.stamp = msg->header.stamp; - poseROS.header.frame_id = string("/world"); + poseROS.header.frame_id = string("world"); poseROS.pose.position.x = pose(0); poseROS.pose.position.y = pose(1); poseROS.pose.position.z = pose(2); @@ -98,7 +98,7 @@ void odom_callback(const nav_msgs::Odometry::ConstPtr& msg) yprVel(1) = -atan2(vel(2), norm(vel.rows(0,1),2)); yprVel(2) = 0; q = R_to_quaternion(ypr_to_R(yprVel)); - velROS.header.frame_id = string("/world"); + velROS.header.frame_id = string("world"); velROS.header.stamp = msg->header.stamp; velROS.ns = string("velocity"); velROS.id = 0; @@ -167,7 +167,7 @@ void odom_callback(const nav_msgs::Odometry::ConstPtr& msg) } } } - covROS.header.frame_id = string("/world"); + covROS.header.frame_id = string("world"); covROS.header.stamp = msg->header.stamp; covROS.ns = string("covariance"); covROS.id = 0; @@ -216,7 +216,7 @@ void odom_callback(const nav_msgs::Odometry::ConstPtr& msg) } } } - covVelROS.header.frame_id = string("/world"); + covVelROS.header.frame_id = string("world"); covVelROS.header.stamp = msg->header.stamp; covVelROS.ns = string("covariance_velocity"); covVelROS.id = 0; @@ -246,7 +246,7 @@ void odom_callback(const nav_msgs::Odometry::ConstPtr& msg) ros::Time t = msg->header.stamp; if ((t - pt).toSec() > 0.5) { - trajROS.header.frame_id = string("/world"); + trajROS.header.frame_id = string("world"); trajROS.header.stamp = ros::Time::now(); trajROS.ns = string("trajectory"); trajROS.type = visualization_msgs::Marker::LINE_LIST; @@ -287,7 +287,7 @@ void odom_callback(const nav_msgs::Odometry::ConstPtr& msg) } // Sensor availability - sensorROS.header.frame_id = string("/world"); + sensorROS.header.frame_id = string("world"); sensorROS.header.stamp = msg->header.stamp; sensorROS.ns = string("sensor"); sensorROS.type = visualization_msgs::Marker::TEXT_VIEW_FACING; @@ -376,7 +376,7 @@ void odom_callback(const nav_msgs::Odometry::ConstPtr& msg) colvec q90 = R_to_quaternion(ypr_to_R(p90)); transform90.setRotation(tf::Quaternion(q90(1), q90(2), q90(3), q90(0))); - broadcaster->sendTransform(tf::StampedTransform(transform, msg->header.stamp, string("/world"), string("/base"))); + broadcaster->sendTransform(tf::StampedTransform(transform, msg->header.stamp, string("world"), string("/base"))); broadcaster->sendTransform(tf::StampedTransform(transform45, msg->header.stamp, string("/base"), string("/laser"))); broadcaster->sendTransform(tf::StampedTransform(transform45, msg->header.stamp, string("/base"), string("/vision"))); broadcaster->sendTransform(tf::StampedTransform(transform90, msg->header.stamp, string("/base"), string("/height"))); @@ -443,7 +443,7 @@ int main(int argc, char** argv) n.param("color/a", color_a, 1.0); n.param("origin", origin, false); n.param("robot_scale", scale, 2.0); - n.param("frame_id", _frame_id, string("/world") ); + n.param("frame_id", _frame_id, string("world") ); n.param("cross_config", cross_config, false); n.param("tf45", tf45, false); From 1207fbc2bb9d47abe44b7dd98abf9796cf491ee8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E8=B5=B5=E5=A2=9E=E5=90=9B?= <32793431+Junking1@users.noreply.github.com> Date: Fri, 7 May 2021 09:36:00 +0800 Subject: [PATCH 3/5] Update CMakeLists.txt --- fast_planner/bspline_opt/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fast_planner/bspline_opt/CMakeLists.txt b/fast_planner/bspline_opt/CMakeLists.txt index 7fd15181a..71db5ba17 100755 --- a/fast_planner/bspline_opt/CMakeLists.txt +++ b/fast_planner/bspline_opt/CMakeLists.txt @@ -10,7 +10,6 @@ find_package(catkin REQUIRED COMPONENTS std_msgs visualization_msgs cv_bridge - nlopt plan_env ) @@ -36,4 +35,5 @@ add_library( bspline_opt ) target_link_libraries( bspline_opt ${catkin_LIBRARIES} + nlopt ) From 6bb99c80ce2acc543c0155a7175bdd8fbfa7b6e2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E8=B5=B5=E5=A2=9E=E5=90=9B?= <32793431+Junking1@users.noreply.github.com> Date: Fri, 7 May 2021 09:36:41 +0800 Subject: [PATCH 4/5] Update README.md --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 2edbc66f6..a39a3c847 100644 --- a/README.md +++ b/README.md @@ -65,7 +65,7 @@ after that,you can test the fast-planner,run the following commands to setup ``` sudo apt-get install libarmadillo-dev cd ${YOUR_WORKSPACE_PATH}/src - git clone https://github.com/HKUST-Aerial-Robotics/Fast-Planner.git + git clone https://github.com/Junking1/Fast-Planner-for-ubuntu20.04.git cd ../ catkin_make ``` From 2735863f4113bf0ba00f4f9454d71b5e1d91331c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E8=B5=B5=E5=A2=9E=E5=90=9B?= <32793431+Junking1@users.noreply.github.com> Date: Fri, 7 May 2021 10:06:42 +0800 Subject: [PATCH 5/5] Update README.md --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index a39a3c847..94d1af25a 100644 --- a/README.md +++ b/README.md @@ -51,7 +51,7 @@ Please kindly star :star: this project if it helps you. We take great efforts to # Quick start with ubuntu 20.04 -if Ubuntu 20.04,you should install nplot with the source code +if Ubuntu 20.04,you should install nlopt with the source code ``` git clone https://github.com/stevengj/nlopt.git cd nlopt