Skip to content

Ubuntu 20.04 #107

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 5 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
35 changes: 34 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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 nlopt 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/Junking1/Fast-Planner-for-ubuntu20.04.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 ../
Expand Down
2 changes: 1 addition & 1 deletion fast_planner/bspline_opt/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@ find_package(catkin REQUIRED COMPONENTS
std_msgs
visualization_msgs
cv_bridge
nlopt
plan_env
)

Expand All @@ -36,4 +35,5 @@ add_library( bspline_opt
)
target_link_libraries( bspline_opt
${catkin_LIBRARIES}
nlopt
)
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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")));
Expand Down Expand Up @@ -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);
Expand Down