Note: The default ITS GitLab runner is a shared resource and is subject to slowdowns during heavy usage.
You can run your own GitLab runner that is dedicated just to your group if you need to avoid processing delays.

Commit 298ea6ba authored by Dushyanth Ganesan's avatar Dushyanth Ganesan
Browse files

commiting fast planner to master

parent 04b0d3a9
fast_planner/.vscode
.vscode/
.clang-format
This diff is collapsed.
# Fast-Planner
**Fast-Planner** is developed aiming to enable quadrotor fast flight in complex unknown environments. It contains a rich set of carefully designed planning algorithms.
**News**:
- __Mar 13, 2021__: Code for fast autonomous exploration is available now! Check this [repo](https://github.com/HKUST-Aerial-Robotics/FUEL) for more details.
- __Oct 20, 2020__: Fast-Planner is extended and applied to fast autonomous exploration. Check this [repo](https://github.com/HKUST-Aerial-Robotics/FUEL) for more details.
__Authors__: [Boyu Zhou](http://boyuzhou.net) and [Shaojie Shen](http://uav.ust.hk/group/) from the [HUKST Aerial Robotics Group](http://uav.ust.hk/), [Fei Gao](https://ustfei.com/) from [ZJU FAST Lab](http://www.kivact.com/).
<!-- - __B-spline trajectory optimization guided by topological paths__:
<p align="center">
<img src="https://github.com/HKUST-Aerial-Robotics/TopoTraj/blob/master/files/icra20_1.gif" width = "420" height = "237"/>
<img src="https://github.com/HKUST-Aerial-Robotics/TopoTraj/blob/master/files/icra20_2.gif" width = "420" height = "237"/>
</p> -->
<p align="center">
<img src="files/raptor1.gif" width = "400" height = "225"/>
<img src="files/raptor2.gif" width = "400" height = "225"/>
<img src="files/icra20_2.gif" width = "400" height = "225"/>
<img src="files/ral19_2.gif" width = "400" height = "225"/>
<!-- <img src="files/icra20_1.gif" width = "320" height = "180"/> -->
</p>
Complete videos:
[video1](https://www.youtube.com/watch?v=NvR8Lq2pmPg&feature=emb_logo),
[video2](https://www.youtube.com/watch?v=YcEaFTjs-a0),
[video3](https://www.youtube.com/watch?v=toGhoGYyoAY).
Demonstrations about this work have been reported on the IEEE Spectrum: [page1](https://spectrum.ieee.org/automaton/robotics/robotics-hardware/video-friday-nasa-lemur-robot), [page2](https://spectrum.ieee.org/automaton/robotics/robotics-hardware/video-friday-india-space-humanoid-robot),
[page3](https://spectrum.ieee.org/automaton/robotics/robotics-hardware/video-friday-soft-exoskeleton-glove-extra-thumb) (search for _HKUST_ in the pages).
To run this project in minutes, check [Quick Start](#1-Quick-Start). Check other sections for more detailed information.
Please kindly star :star: this project if it helps you. We take great efforts to develope and maintain it :grin::grin:.
## Table of Contents
* [Quick Start](#1-Quick-Start)
* [Algorithms and Papers](#2-Algorithms-and-Papers)
* [Setup and Config](#3-Setup-and-Config)
* [Run Simulations](#4-run-simulations)
* [Use in Your Application](#5-use-in-your-application)
* [Updates](#6-updates)
## 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
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).
## 2. Algorithms and Papers
The project contains a collection of robust and computationally efficient algorithms for quadrotor fast flight:
* Kinodynamic path searching
* B-spline-based trajectory optimization
* Topological path searching and path-guided optimization
* Perception-aware planning strategy (to appear)
These methods are detailed in our papers listed below.
Please cite at least one of our papers if you use this project in your research: [Bibtex](files/bib.txt).
- [__Robust and Efficient Quadrotor Trajectory Generation for Fast Autonomous Flight__](https://ieeexplore.ieee.org/document/8758904), Boyu Zhou, Fei Gao, Luqi Wang, Chuhao Liu and Shaojie Shen, IEEE Robotics and Automation Letters (**RA-L**), 2019.
- [__Robust Real-time UAV Replanning Using Guided Gradient-based Optimization and Topological Paths__](https://arxiv.org/abs/1912.12644), Boyu Zhou, Fei Gao, Jie Pan and Shaojie Shen, IEEE International Conference on Robotics and Automation (__ICRA__), 2020.
- [__RAPTOR: Robust and Perception-aware Trajectory Replanning for Quadrotor Fast Flight__](https://arxiv.org/abs/2007.03465), Boyu Zhou, Jie Pan, Fei Gao and Shaojie Shen, IEEE Transactions on Robotics (__T-RO__).
All planning algorithms along with other key modules, such as mapping, are implemented in __fast_planner__:
- __plan_env__: The online mapping algorithms. It takes in depth image (or point cloud) and camera pose (odometry) pairs as input, do raycasting to update a probabilistic volumetric map, and build an Euclidean signed distance filed (ESDF) for the planning system.
- __path_searching__: Front-end path searching algorithms.
Currently it includes a kinodynamic path searching that respects the dynamics of quadrotors.
It also contains a sampling-based topological path searching algorithm to generate multiple topologically distinctive paths that capture the structure of the 3D environments.
- __bspline__: A implementation of the B-spline-based trajectory representation.
- __bspline_opt__: The gradient-based trajectory optimization using B-spline trajectory.
- __active_perception__: Perception-aware planning strategy, which enable to quadrotor to actively observe and avoid unknown obstacles, to appear in the future.
- __plan_manage__: High-level modules that schedule and call the mapping and planning algorithms. Interfaces for launching the whole system, as well as the configuration files are contained here.
Besides the folder __fast_planner__, a lightweight __uav_simulator__ is used for testing.
## 3. Setup and Config
### Prerequisites
1. Our software is developed and tested in Ubuntu 16.04(ROS Kinetic) and 18.04(ROS Melodic). Follow the documents to install [Kinetic](http://wiki.ros.org/kinetic/Installation/Ubuntu) or [Melodic](http://wiki.ros.org/melodic/Installation/Ubuntu) according to your Ubuntu version.
2. We use [**NLopt**](https://nlopt.readthedocs.io/en/latest/NLopt_Installation) to solve the non-linear optimization problem. The __uav_simulator__ depends on the C++ linear algebra library __Armadillo__. The two dependencies can be installed by the following command, in which `${ROS_VERSION_NAME}` is the name of your ROS release.
```
sudo apt-get install libarmadillo-dev ros_${ROS_VERSION_NAME}_nlopt
```
### Build on ROS
After the prerequisites are satisfied, you can clone this repository to your catkin workspace and catkin_make. A new workspace is recommended:
```
cd ${YOUR_WORKSPACE_PATH}/src
git clone https://github.com/HKUST-Aerial-Robotics/Fast-Planner.git
cd ../
catkin_make
```
If you encounter problems in this step, please first refer to existing __issues__, __pull requests__ and __Google__ before raising a new issue.
Now you are ready to [run a simulation](#4-run-simulations).
### Use GPU Depth Rendering (can be skipped optionally)
This step is not mandatory for running the simulations. However, if you want to run the more realistic depth camera in __uav_simulator__, installation of [CUDA Toolkit](https://developer.nvidia.com/cuda-toolkit) is needed. Otherwise, a less realistic depth sensor model will be used.
The **local_sensing** package in __uav_simulator__ has the option of using GPU or CPU to render the depth sensor measurement. By default, it is set to CPU version in CMakeLists:
```
set(ENABLE_CUDA false)
# set(ENABLE_CUDA true)
```
However, we STRONGLY recommend the GPU version, because it generates depth images more like a real depth camera.
To enable the GPU depth rendering, set ENABLE_CUDA to true, and also remember to change the 'arch' and 'code' flags according to your graphics card devices. You can check the right code [here](https://github.com/tpruvot/ccminer/wiki/Compatibility).
```
set(CUDA_NVCC_FLAGS
-gencode arch=compute_61,code=sm_61;
)
```
For installation of CUDA, please go to [CUDA ToolKit](https://developer.nvidia.com/cuda-toolkit)
## 4. Run Simulations
Run [Rviz](http://wiki.ros.org/rviz) with our configuration firstly:
```
<!-- go to your workspace and run: -->
source devel/setup.bash
roslaunch plan_manage rviz.launch
```
Then run the quadrotor simulator and __Fast-Planner__.
Several examples are provided below:
### Kinodynamic Path Searching & B-spline Optimization
In this method, a kinodynamic path searching finds a safe, dynamically feasible, and minimum-time initial trajectory in the discretized control space.
Then the smoothness and clearance of the trajectory are improved by a B-spline optimization.
To test this method, run:
```
<!-- open a new terminal, go to your workspace and run: -->
source devel/setup.bash
roslaunch plan_manage kino_replan.launch
```
Normally, you will find the randomly generated map and the drone model in ```Rviz```. At this time, you can trigger the planner using the ```2D Nav Goal``` tool. When a point is clicked in ```Rviz```, a new trajectory will be generated immediately and executed by the drone. A sample is displayed below:
<!-- add some gif here -->
<p id="demo1" align="center">
<img src="files/ral19_3.gif" width = "480" height = "270"/>
</p>
Related algorithms are detailed in [this paper](https://ieeexplore.ieee.org/document/8758904).
### Topological Path Searching & Path-guided Optimization
This method features searching for multiple trajectories in distinctive topological classes. Thanks to the strategy, the solution space is explored more thoroughly, avoiding local minima and yielding better solutions.
Similarly, run:
```
<!-- open a new terminal, go to your workspace and run: -->
source devel/setup.bash
roslaunch plan_manage topo_replan.launch
```
then you will find the random map generated and can use the ```2D Nav Goal``` to trigger the planner:
<!-- add some gif here -->
<p align="center">
<img src="files/icra20_3.gif" width = "480" height = "270"/>
</p>
Related algorithms are detailed in [this paper](https://arxiv.org/abs/1912.12644).
### Perception-aware Replanning
The code will be released after the publication of [associated paper](https://arxiv.org/abs/2007.03465).
## 5. Use in Your Application
If you have successfully run the simulation and want to use __Fast-Planner__ in your project,
please explore the files kino_replan.launch or topo_replan.launch.
Important parameters that may be changed in your usage are contained and documented.
Note that in our configuration, the size of depth image is 640x480.
For higher map fusion efficiency we do downsampling (in kino_algorithm.xml, skip_pixel = 2).
If you use depth images with lower resolution (like 256x144), you might disable the downsampling by setting skip_pixel = 1. Also, the _depth_scaling_factor_ is set to 1000, which may need to be changed according to your device.
Finally, for setup problem, like compilation error caused by different versions of ROS/Eigen, please first refer to existing __issues__, __pull request__, and __Google__ before raising a new issue. Insignificant issue will receive no reply.
## 6. Updates
- __Oct 20, 2020__: Fast-Planner is extended and applied to fast autonomous exploration. Check this [repo](https://github.com/HKUST-Aerial-Robotics/FUEL) for more details.
- __July 5, 2020__: We will release the implementation of paper: _RAPTOR: Robust and Perception-aware Trajectory Replanning for Quadrotor Fast Flight_ (submitted to TRO, under review) in the future.
- __April 12, 2020__: The implementation of the ICRA2020 paper: _Robust Real-time UAV Replanning Using Guided Gradient-based Optimization and Topological Paths_ is available.
- __Jan 30, 2020__: The volumetric mapping is integrated with our planner. It takes in depth image and camera pose pairs as input, do raycasting to fuse the measurements, and build a Euclidean signed distance field (ESDF) for the planning module.
## Acknowledgements
We use **NLopt** for non-linear optimization.
## Licence
The source code is released under [GPLv3](http://www.gnu.org/licenses/) license.
## Disclaimer
This is research code, it is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of merchantability or fitness for a particular purpose.
# camera, map, range, path, traj, cmd
# /vins_estimator/camera_pose
rosbag record /pcl_render_node/camera_pose /sdf_map/occupancy_inflate /sdf_map/update_range /planning_vis/topo_path /planning_vis/trajectory /planning/state
\ No newline at end of file
cmake_minimum_required(VERSION 2.8.3)
project(bspline)
find_package(Eigen3 REQUIRED)
find_package(PCL 1.7 REQUIRED)
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
visualization_msgs
plan_env
cv_bridge
)
catkin_package(
INCLUDE_DIRS include
LIBRARIES bspline
CATKIN_DEPENDS
# DEPENDS system_lib
)
include_directories(
SYSTEM
include
${catkin_INCLUDE_DIRS}
${Eigen3_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
)
set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS} -O3 -Wall")
add_library( bspline
src/non_uniform_bspline.cpp
)
target_link_libraries( bspline
${catkin_LIBRARIES}
)
/**
* This file is part of Fast-Planner.
*
* Copyright 2019 Boyu Zhou, Aerial Robotics Group, Hong Kong University of Science and Technology, <uav.ust.hk>
* Developed by Boyu Zhou <bzhouai at connect dot ust dot hk>, <uv dot boyuzhou at gmail dot com>
* for more information see <https://github.com/HKUST-Aerial-Robotics/Fast-Planner>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* Fast-Planner is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Fast-Planner is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with Fast-Planner. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _NON_UNIFORM_BSPLINE_H_
#define _NON_UNIFORM_BSPLINE_H_
#include <Eigen/Eigen>
#include <algorithm>
#include <iostream>
using namespace std;
namespace fast_planner {
// An implementation of non-uniform B-spline with different dimensions
// It also represents uniform B-spline which is a special case of non-uniform
class NonUniformBspline {
private:
// control points for B-spline with different dimensions.
// Each row represents one single control point
// The dimension is determined by column number
// e.g. B-spline with N points in 3D space -> Nx3 matrix
Eigen::MatrixXd control_points_;
int p_, n_, m_; // p degree, n+1 control points, m = n+p+1
Eigen::VectorXd u_; // knots vector
double interval_; // knot span \delta t
Eigen::MatrixXd getDerivativeControlPoints();
double limit_vel_, limit_acc_, limit_ratio_; // physical limits and time adjustment ratio
public:
NonUniformBspline() {}
NonUniformBspline(const Eigen::MatrixXd& points, const int& order, const double& interval);
~NonUniformBspline();
// initialize as an uniform B-spline
void setUniformBspline(const Eigen::MatrixXd& points, const int& order, const double& interval);
// get / set basic bspline info
void setKnot(const Eigen::VectorXd& knot);
Eigen::VectorXd getKnot();
Eigen::MatrixXd getControlPoint();
double getInterval();
void getTimeSpan(double& um, double& um_p);
pair<Eigen::VectorXd, Eigen::VectorXd> getHeadTailPts();
// compute position / derivative
Eigen::VectorXd evaluateDeBoor(const double& u); // use u \in [up, u_mp]
Eigen::VectorXd evaluateDeBoorT(const double& t); // use t \in [0, duration]
NonUniformBspline getDerivative();
// 3D B-spline interpolation of points in point_set, with boundary vel&acc
// constraints
// input : (K+2) points with boundary vel/acc; ts
// output: (K+6) control_pts
static void parameterizeToBspline(const double& ts, const vector<Eigen::Vector3d>& point_set,
const vector<Eigen::Vector3d>& start_end_derivative,
Eigen::MatrixXd& ctrl_pts);
/* check feasibility, adjust time */
void setPhysicalLimits(const double& vel, const double& acc);
bool checkFeasibility(bool show = false);
double checkRatio();
void lengthenTime(const double& ratio);
bool reallocateTime(bool show = false);
/* for performance evaluation */
double getTimeSum();
double getLength(const double& res = 0.01);
double getJerk();
void getMeanAndMaxVel(double& mean_v, double& max_v);
void getMeanAndMaxAcc(double& mean_a, double& max_a);
void recomputeInit();
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
} // namespace fast_planner
#endif
\ No newline at end of file
<?xml version="1.0"?>
<package format="2">
<name>bspline</name>
<version>0.0.0</version>
<description>The bspline package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="bzhouai@todo.todo">bzhouai</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 multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/bspline</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, 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 depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>plan_env</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<build_export_depend>plan_env</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>plan_env</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>
/**
* This file is part of Fast-Planner.
*
* Copyright 2019 Boyu Zhou, Aerial Robotics Group, Hong Kong University of Science and Technology, <uav.ust.hk>
* Developed by Boyu Zhou <bzhouai at connect dot ust dot hk>, <uv dot boyuzhou at gmail dot com>
* for more information see <https://github.com/HKUST-Aerial-Robotics/Fast-Planner>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* Fast-Planner is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Fast-Planner is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with Fast-Planner. If not, see <http://www.gnu.org/licenses/>.
*/
#include "bspline/non_uniform_bspline.h"
#include <ros/ros.h>
namespace fast_planner {
NonUniformBspline::NonUniformBspline(const Eigen::MatrixXd& points, const int& order,
const double& interval) {
setUniformBspline(points, order, interval);
}
NonUniformBspline::~NonUniformBspline() {}
void NonUniformBspline::setUniformBspline(const Eigen::MatrixXd& points, const int& order,
const double& interval) {
control_points_ = points;
p_ = order;
interval_ = interval;
n_ = points.rows() - 1;
m_ = n_ + p_ + 1;
u_ = Eigen::VectorXd::Zero(m_ + 1);
for (int i = 0; i <= m_; ++i) {
if (i <= p_) {
u_(i) = double(-p_ + i) * interval_;
} else if (i > p_ && i <= m_ - p_) {
u_(i) = u_(i - 1) + interval_;
} else if (i > m_ - p_) {
u_(i) = u_(i - 1) + interval_;
}
}
}
void NonUniformBspline::setKnot(const Eigen::VectorXd& knot) { this->u_ = knot; }
Eigen::VectorXd NonUniformBspline::getKnot() { return this->u_; }
void NonUniformBspline::getTimeSpan(double& um, double& um_p) {
um = u_(p_);
um_p = u_(m_ - p_);
}
Eigen::MatrixXd NonUniformBspline::getControlPoint() { return control_points_; }
pair<Eigen::VectorXd, Eigen::VectorXd> NonUniformBspline::getHeadTailPts() {
Eigen::VectorXd head = evaluateDeBoor(u_(p_));
Eigen::VectorXd tail = evaluateDeBoor(u_(m_ - p_));
return make_pair(head, tail);
}
Eigen::VectorXd NonUniformBspline::evaluateDeBoor(const double& u) {
double ub = min(max(u_(p_), u), u_(m_ - p_));
// determine which [ui,ui+1] lay in
int k = p_;
while (true) {
if (u_(k + 1) >= ub) break;
++k;
}
/* deBoor's alg */
vector<Eigen::VectorXd> d;
for (int i = 0; i <= p_; ++i) {
d.push_back(control_points_.row(k - p_ + i));
// cout << d[i].transpose() << endl;
}
for (int r = 1; r <= p_; ++r) {
for (int i = p_; i >= r; --i) {
double alpha = (ub - u_[i + k - p_]) / (u_[i + 1 + k - r] - u_[i + k - p_]);
// cout << "alpha: " << alpha << endl;
d[i] = (1 - alpha) * d[i - 1] + alpha * d[i];
}
}
return d[p_];
}
Eigen::VectorXd NonUniformBspline::evaluateDeBoorT(const double& t) {
return evaluateDeBoor(t + u_(p_));
}
Eigen::MatrixXd NonUniformBspline::getDerivativeControlPoints() {
// The derivative of a b-spline is also a b-spline, its order become p_-1
// control point Qi = p_*(Pi+1-Pi)/(ui+p_+1-ui+1)
Eigen::MatrixXd ctp = Eigen::MatrixXd::Zero(control_points_.rows() - 1, control_points_.cols());
for (int i = 0; i < ctp.rows(); ++i) {
ctp.row(i) =
p_ * (control_points_.row(i + 1) - control_points_.row(i)) / (u_(i + p_ + 1) - u_(i + 1));
}