├── .gitignore ├── .vscode ├── c_cpp_properties.json └── tasks.json ├── LICENSE ├── README.md ├── modified_realsense2_camera.zip ├── pictures ├── comp.jpg ├── indoor.gif ├── outdoor.gif ├── realsense.PNG ├── sim_demo.gif └── title.gif └── src ├── CMakeLists.txt ├── planner ├── bspline_opt │ ├── CMakeLists.txt │ ├── include │ │ └── bspline_opt │ │ │ ├── bspline_optimizer.h │ │ │ ├── gradient_descent_optimizer.h │ │ │ ├── lbfgs.hpp │ │ │ └── uniform_bspline.h │ ├── package.xml │ └── src │ │ ├── bspline_optimizer.cpp │ │ ├── gradient_descent_optimizer.cpp │ │ └── uniform_bspline.cpp ├── path_searching │ ├── CMakeLists.txt │ ├── include │ │ └── path_searching │ │ │ └── dyn_a_star.h │ ├── package.xml │ └── src │ │ └── dyn_a_star.cpp ├── plan_env │ ├── CMakeLists.txt │ ├── include │ │ └── plan_env │ │ │ ├── grid_map.h │ │ │ └── raycast.h │ ├── package.xml │ └── src │ │ ├── grid_map.cpp │ │ └── raycast.cpp ├── plan_manage │ ├── CMakeLists.txt │ ├── include │ │ └── plan_manage │ │ │ ├── ego_replan_fsm.h │ │ │ ├── plan_container.hpp │ │ │ └── planner_manager.h │ ├── launch │ │ ├── advanced_param.xml │ │ ├── default.rviz │ │ ├── run_in_sim.launch │ │ ├── rviz.launch │ │ ├── simple_run.launch │ │ └── simulator.xml │ ├── msg │ │ ├── Bspline.msg │ │ └── DataDisp.msg │ ├── package.xml │ └── src │ │ ├── ego_planner_node.cpp │ │ ├── ego_replan_fsm.cpp │ │ ├── planner_manager.cpp │ │ └── traj_server.cpp └── traj_utils │ ├── CMakeLists.txt │ ├── include │ └── traj_utils │ │ ├── planning_visualization.h │ │ └── polynomial_traj.h │ ├── package.xml │ └── src │ ├── planning_visualization.cpp │ └── polynomial_traj.cpp └── uav_simulator ├── Utils ├── cmake_utils │ ├── CMakeLists.txt │ ├── cmake │ │ ├── arch.cmake │ │ ├── cmake_modules.cmake │ │ └── color.cmake │ ├── cmake_modules │ │ ├── FindEigen.cmake │ │ ├── FindGSL.cmake │ │ └── FindmvIMPACT.cmake │ └── package.xml ├── multi_map_server │ ├── CMakeLists.txt │ ├── Makefile │ ├── include │ │ └── multi_map_server │ │ │ ├── Map2D.h │ │ │ └── Map3D.h │ ├── mainpage.dox │ ├── msg │ │ ├── MultiOccupancyGrid.msg │ │ ├── MultiSparseMap3D.msg │ │ ├── SparseMap3D.msg │ │ └── VerticalOccupancyGridList.msg │ ├── package.xml │ └── src │ │ ├── multi_map_server │ │ ├── __init__.py │ │ └── msg │ │ │ ├── _MultiOccupancyGrid.py │ │ │ ├── _MultiSparseMap3D.py │ │ │ ├── _SparseMap3D.py │ │ │ ├── _VerticalOccupancyGridList.py │ │ │ └── __init__.py │ │ ├── multi_map_visualization.cc │ │ └── unused │ │ └── multi_map_server.cc ├── odom_visualization │ ├── CMakeLists.txt │ ├── Makefile │ ├── mainpage.dox │ ├── meshes │ │ └── hummingbird.mesh │ ├── package.xml │ └── src │ │ ├── odom_visualization.cpp │ │ └── odom_visualization.cpp~ ├── pose_utils │ ├── CMakeLists.txt │ ├── Makefile │ ├── include │ │ └── pose_utils.h │ ├── package.xml │ └── src │ │ ├── pose_utils.cpp │ │ └── pose_utils.cpp~ ├── quadrotor_msgs │ ├── CMakeLists.txt │ ├── cmake │ │ └── FindEigen3.cmake │ ├── include │ │ └── quadrotor_msgs │ │ │ ├── comm_types.h │ │ │ ├── decode_msgs.h │ │ │ └── encode_msgs.h │ ├── msg │ │ ├── AuxCommand.msg │ │ ├── Corrections.msg │ │ ├── Gains.msg │ │ ├── LQRTrajectory.msg │ │ ├── Odometry.msg │ │ ├── OutputData.msg │ │ ├── PPROutputData.msg │ │ ├── PolynomialTrajectory.msg │ │ ├── PolynomialTrajectory.msg~ │ │ ├── PositionCommand.msg │ │ ├── PositionCommand.msg~ │ │ ├── SO3Command.msg │ │ ├── Serial.msg │ │ ├── StatusData.msg │ │ └── TRPYCommand.msg │ ├── package.xml │ └── src │ │ ├── decode_msgs.cpp │ │ ├── encode_msgs.cpp │ │ └── quadrotor_msgs │ │ ├── __init__.py │ │ ├── __init__.pyc │ │ └── msg │ │ ├── _AuxCommand.py │ │ ├── _Corrections.py │ │ ├── _Gains.py │ │ ├── _OutputData.py │ │ ├── _PPROutputData.py │ │ ├── _PositionCommand.py │ │ ├── _SO3Command.py │ │ ├── _Serial.py │ │ ├── _StatusData.py │ │ ├── _TRPYCommand.py │ │ └── __init__.py ├── rviz_plugins │ ├── CMakeLists.txt │ ├── config │ │ └── rviz_config.rviz │ ├── package.xml │ ├── plugin_description.xml │ └── src │ │ ├── aerialmap_display.cpp │ │ ├── aerialmap_display.h │ │ ├── gamelikeinput.cpp │ │ ├── gamelikeinput.hpp │ │ ├── goal_tool.cpp │ │ ├── goal_tool.h │ │ ├── multi_probmap_display.cpp │ │ ├── multi_probmap_display.h │ │ ├── pose_tool.cpp │ │ ├── pose_tool.h │ │ ├── probmap_display.cpp │ │ └── probmap_display.h ├── uav_utils │ ├── CMakeLists.txt │ ├── include │ │ └── uav_utils │ │ │ ├── converters.h │ │ │ ├── geometry_utils.h │ │ │ └── utils.h │ ├── package.xml │ ├── scripts │ │ ├── odom_to_euler.py │ │ ├── send_odom.py │ │ ├── tf_assist.py │ │ └── topic_statistics.py │ └── src │ │ └── uav_utils_test.cpp └── waypoint_generator │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ ├── sample_waypoints.h │ └── waypoint_generator.cpp ├── local_sensing ├── .vscode │ └── settings.json ├── CMakeLists.txt ├── CMakeModules │ ├── FindCUDA.cmake │ ├── FindCUDA │ │ ├── make2cmake.cmake │ │ ├── parse_cubin.cmake │ │ └── run_nvcc.cmake │ ├── FindEigen.cmake │ └── FindEigen.cmake~ ├── cfg │ └── local_sensing_node.cfg ├── package.xml ├── params │ └── camera.yaml └── src │ ├── AlignError.h │ ├── ceres_extensions.h │ ├── csv_convert.py │ ├── cuda_exception.cuh │ ├── depth_render.cu │ ├── depth_render.cuh │ ├── device_image.cuh │ ├── empty.cpp │ ├── empty.h │ ├── euroc.cpp │ ├── helper_math.h │ ├── pcl_render_node.cpp │ └── pointcloud_render_node.cpp ├── map_generator ├── .vscode │ └── c_cpp_properties.json ├── CMakeLists.txt ├── package.xml └── src │ └── random_forest_sensing.cpp ├── mockamap ├── CMakeLists.txt ├── config │ └── rviz.rviz ├── include │ ├── maps.hpp │ └── perlinnoise.hpp ├── launch │ ├── maze2d.launch │ ├── maze3d.launch │ ├── mockamap.launch │ ├── perlin3d.launch │ └── post2d.launch ├── package.xml └── src │ ├── .clang-format │ ├── ces_randommap.cpp │ ├── maps.cpp │ ├── mockamap.cpp │ └── perlinnoise.cpp ├── so3_control ├── CMakeLists.txt ├── config │ ├── corrections_hummingbird.yaml │ ├── corrections_pelican.yaml │ ├── gains.yaml │ ├── gains_hummingbird.yaml │ └── gains_pelican.yaml ├── include │ └── so3_control │ │ └── SO3Control.h ├── mainpage.dox ├── nodelet_plugin.xml ├── package.xml └── src │ ├── SO3Control.cpp │ ├── control_example.cpp │ └── so3_control_nodelet.cpp └── so3_quadrotor_simulator ├── CMakeLists.txt ├── config └── rviz.rviz ├── include ├── ode │ ├── CHANGELOG │ ├── Jamroot │ ├── README │ ├── boost │ │ └── numeric │ │ │ ├── odeint.hpp │ │ │ └── odeint │ │ │ ├── algebra │ │ │ ├── array_algebra.hpp │ │ │ ├── default_operations.hpp │ │ │ ├── detail │ │ │ │ ├── for_each.hpp │ │ │ │ ├── macros.hpp │ │ │ │ └── reduce.hpp │ │ │ ├── fusion_algebra.hpp │ │ │ ├── range_algebra.hpp │ │ │ └── vector_space_algebra.hpp │ │ │ ├── config.hpp │ │ │ ├── external │ │ │ ├── gsl │ │ │ │ └── gsl_wrapper.hpp │ │ │ ├── mkl │ │ │ │ └── mkl_operations.hpp │ │ │ ├── mtl4 │ │ │ │ ├── implicit_euler_mtl4.hpp │ │ │ │ └── mtl4_resize.hpp │ │ │ ├── thrust │ │ │ │ ├── thrust_algebra.hpp │ │ │ │ ├── thrust_operations.hpp │ │ │ │ └── thrust_resize.hpp │ │ │ ├── vexcl │ │ │ │ └── vexcl_resize.hpp │ │ │ └── viennacl │ │ │ │ ├── viennacl_operations.hpp │ │ │ │ └── viennacl_resize.hpp │ │ │ ├── integrate │ │ │ ├── detail │ │ │ │ ├── integrate_adaptive.hpp │ │ │ │ ├── integrate_const.hpp │ │ │ │ ├── integrate_n_steps.hpp │ │ │ │ └── integrate_times.hpp │ │ │ ├── integrate.hpp │ │ │ ├── integrate_adaptive.hpp │ │ │ ├── integrate_const.hpp │ │ │ ├── integrate_n_steps.hpp │ │ │ ├── integrate_times.hpp │ │ │ ├── null_observer.hpp │ │ │ └── observer_collection.hpp │ │ │ ├── stepper │ │ │ ├── adams_bashforth.hpp │ │ │ ├── adams_bashforth_moulton.hpp │ │ │ ├── adams_moulton.hpp │ │ │ ├── base │ │ │ │ ├── algebra_stepper_base.hpp │ │ │ │ ├── explicit_error_stepper_base.hpp │ │ │ │ ├── explicit_error_stepper_fsal_base.hpp │ │ │ │ ├── explicit_stepper_base.hpp │ │ │ │ └── symplectic_rkn_stepper_base.hpp │ │ │ ├── bulirsch_stoer.hpp │ │ │ ├── bulirsch_stoer_dense_out.hpp │ │ │ ├── controlled_runge_kutta.hpp │ │ │ ├── controlled_step_result.hpp │ │ │ ├── dense_output_runge_kutta.hpp │ │ │ ├── detail │ │ │ │ ├── adams_bashforth_call_algebra.hpp │ │ │ │ ├── adams_bashforth_coefficients.hpp │ │ │ │ ├── adams_moulton_call_algebra.hpp │ │ │ │ ├── adams_moulton_coefficients.hpp │ │ │ │ ├── generic_rk_algorithm.hpp │ │ │ │ ├── generic_rk_call_algebra.hpp │ │ │ │ ├── generic_rk_operations.hpp │ │ │ │ └── rotating_buffer.hpp │ │ │ ├── euler.hpp │ │ │ ├── explicit_error_generic_rk.hpp │ │ │ ├── explicit_generic_rk.hpp │ │ │ ├── generation.hpp │ │ │ ├── generation │ │ │ │ ├── generation_controlled_runge_kutta.hpp │ │ │ │ ├── generation_dense_output_runge_kutta.hpp │ │ │ │ ├── generation_rosenbrock4.hpp │ │ │ │ ├── generation_runge_kutta_cash_karp54.hpp │ │ │ │ ├── generation_runge_kutta_cash_karp54_classic.hpp │ │ │ │ ├── generation_runge_kutta_dopri5.hpp │ │ │ │ ├── generation_runge_kutta_fehlberg78.hpp │ │ │ │ ├── make_controlled.hpp │ │ │ │ └── make_dense_output.hpp │ │ │ ├── implicit_euler.hpp │ │ │ ├── modified_midpoint.hpp │ │ │ ├── rosenbrock4.hpp │ │ │ ├── rosenbrock4_controller.hpp │ │ │ ├── rosenbrock4_dense_output.hpp │ │ │ ├── runge_kutta4.hpp │ │ │ ├── runge_kutta4_classic.hpp │ │ │ ├── runge_kutta_cash_karp54.hpp │ │ │ ├── runge_kutta_cash_karp54_classic.hpp │ │ │ ├── runge_kutta_dopri5.hpp │ │ │ ├── runge_kutta_fehlberg78.hpp │ │ │ ├── stepper_categories.hpp │ │ │ ├── symplectic_euler.hpp │ │ │ ├── symplectic_rkn_sb3a_m4_mclachlan.hpp │ │ │ └── symplectic_rkn_sb3a_mclachlan.hpp │ │ │ ├── util │ │ │ ├── bind.hpp │ │ │ ├── copy.hpp │ │ │ ├── detail │ │ │ │ ├── is_range.hpp │ │ │ │ └── less_with_sign.hpp │ │ │ ├── is_pair.hpp │ │ │ ├── is_resizeable.hpp │ │ │ ├── resize.hpp │ │ │ ├── resizer.hpp │ │ │ ├── same_instance.hpp │ │ │ ├── same_size.hpp │ │ │ ├── state_wrapper.hpp │ │ │ ├── ublas_wrapper.hpp │ │ │ ├── unit_helper.hpp │ │ │ └── unwrap_reference.hpp │ │ │ └── version.hpp │ └── libs │ │ └── numeric │ │ └── odeint │ │ ├── doc │ │ ├── Jamfile.v2 │ │ ├── acknowledgements.qbk │ │ ├── concepts.qbk │ │ ├── concepts │ │ │ ├── controlled_stepper.qbk │ │ │ ├── dense_output_stepper.qbk │ │ │ ├── error_stepper.qbk │ │ │ ├── implicit_system.qbk │ │ │ ├── state_algebra_operations.qbk │ │ │ ├── state_wrapper.qbk │ │ │ ├── stepper.qbk │ │ │ ├── symplectic_system.qbk │ │ │ └── system.qbk │ │ ├── controlled_stepper_table.qbk │ │ ├── details.qbk │ │ ├── details_bind_member_functions.qbk │ │ ├── details_boost_range.qbk │ │ ├── details_boost_ref.qbk │ │ ├── details_generation_functions.qbk │ │ ├── details_integrate_functions.qbk │ │ ├── details_state_types_algebras_operations.qbk │ │ ├── details_steppers.qbk │ │ ├── examples_table.qbk │ │ ├── getting_started.qbk │ │ ├── html │ │ │ ├── boostbook.css │ │ │ ├── images │ │ │ │ ├── alert.png │ │ │ │ ├── blank.png │ │ │ │ ├── callouts │ │ │ │ │ ├── 1.png │ │ │ │ │ ├── 1.svg │ │ │ │ │ ├── 10.png │ │ │ │ │ ├── 10.svg │ │ │ │ │ ├── 11.png │ │ │ │ │ ├── 11.svg │ │ │ │ │ ├── 12.png │ │ │ │ │ ├── 12.svg │ │ │ │ │ ├── 13.png │ │ │ │ │ ├── 13.svg │ │ │ │ │ ├── 14.png │ │ │ │ │ ├── 14.svg │ │ │ │ │ ├── 15.png │ │ │ │ │ ├── 15.svg │ │ │ │ │ ├── 16.svg │ │ │ │ │ ├── 17.svg │ │ │ │ │ ├── 18.svg │ │ │ │ │ ├── 19.svg │ │ │ │ │ ├── 2.png │ │ │ │ │ ├── 2.svg │ │ │ │ │ ├── 20.svg │ │ │ │ │ ├── 21.svg │ │ │ │ │ ├── 22.svg │ │ │ │ │ ├── 23.svg │ │ │ │ │ ├── 24.svg │ │ │ │ │ ├── 25.svg │ │ │ │ │ ├── 26.svg │ │ │ │ │ ├── 27.svg │ │ │ │ │ ├── 28.svg │ │ │ │ │ ├── 29.svg │ │ │ │ │ ├── 3.png │ │ │ │ │ ├── 3.svg │ │ │ │ │ ├── 30.svg │ │ │ │ │ ├── 4.png │ │ │ │ │ ├── 4.svg │ │ │ │ │ ├── 5.png │ │ │ │ │ ├── 5.svg │ │ │ │ │ ├── 6.png │ │ │ │ │ ├── 6.svg │ │ │ │ │ ├── 7.png │ │ │ │ │ ├── 7.svg │ │ │ │ │ ├── 8.png │ │ │ │ │ ├── 8.svg │ │ │ │ │ ├── 9.png │ │ │ │ │ └── 9.svg │ │ │ │ ├── caution.png │ │ │ │ ├── caution.svg │ │ │ │ ├── draft.png │ │ │ │ ├── home.png │ │ │ │ ├── home.svg │ │ │ │ ├── important.png │ │ │ │ ├── important.svg │ │ │ │ ├── next.png │ │ │ │ ├── next.svg │ │ │ │ ├── next_disabled.png │ │ │ │ ├── note.png │ │ │ │ ├── note.svg │ │ │ │ ├── prev.png │ │ │ │ ├── prev.svg │ │ │ │ ├── prev_disabled.png │ │ │ │ ├── smiley.png │ │ │ │ ├── tip.png │ │ │ │ ├── tip.svg │ │ │ │ ├── toc-blank.png │ │ │ │ ├── toc-minus.png │ │ │ │ ├── toc-plus.png │ │ │ │ ├── up.png │ │ │ │ ├── up.svg │ │ │ │ ├── up_disabled.png │ │ │ │ ├── warning.png │ │ │ │ └── warning.svg │ │ │ ├── logo.jpg │ │ │ ├── phase_lattice_2d_0000.jpg │ │ │ ├── phase_lattice_2d_0100.jpg │ │ │ ├── phase_lattice_2d_1000.jpg │ │ │ └── solar_system.jpg │ │ ├── literature.qbk │ │ ├── make_controlled_table.qbk │ │ ├── make_dense_output_table.qbk │ │ ├── odeint.idx │ │ ├── odeint.qbk │ │ ├── range_table.qbk │ │ ├── stepper_table.qbk │ │ ├── tutorial.qbk │ │ ├── tutorial_chaotic_system.qbk │ │ ├── tutorial_harmonic_oscillator.qbk │ │ ├── tutorial_solar_system.qbk │ │ ├── tutorial_special_topics.qbk │ │ ├── tutorial_stiff_systems.qbk │ │ ├── tutorial_thrust_cuda.qbk │ │ └── tutorial_vexcl_opencl.qbk │ │ ├── examples │ │ ├── 2d_lattice │ │ │ ├── Jamfile.v2 │ │ │ ├── lattice2d.hpp │ │ │ ├── nested_range_algebra.hpp │ │ │ ├── spreading.cpp │ │ │ └── vector_vector_resize.hpp │ │ ├── Jamfile.v2 │ │ ├── bind_member_functions.cpp │ │ ├── bind_member_functions_cpp11.cpp │ │ ├── bulirsch_stoer.cpp │ │ ├── chaotic_system.cpp │ │ ├── elliptic.py │ │ ├── elliptic_functions.cpp │ │ ├── fpu.cpp │ │ ├── generation_functions.cpp │ │ ├── gmpxx │ │ │ └── lorenz_gmpxx.cpp │ │ ├── gram_schmidt.hpp │ │ ├── harmonic_oscillator.cpp │ │ ├── harmonic_oscillator_units.cpp │ │ ├── heun.cpp │ │ ├── list_lattice.cpp │ │ ├── lorenz_point.cpp │ │ ├── mtl │ │ │ ├── Jamfile.v2 │ │ │ ├── gauss_packet.cpp │ │ │ └── implicit_euler_mtl.cpp │ │ ├── my_vector.cpp │ │ ├── phase_oscillator_ensemble.cpp │ │ ├── point_type.hpp │ │ ├── quadmath │ │ │ ├── Jamfile.v2 │ │ │ └── black_hole.cpp │ │ ├── resizing_lattice.cpp │ │ ├── simple1d.cpp │ │ ├── solar_system.agr │ │ ├── solar_system.cpp │ │ ├── stepper_details.cpp │ │ ├── stiff_system.cpp │ │ ├── stochastic_euler.cpp │ │ ├── stuart_landau.cpp │ │ ├── thrust │ │ │ ├── Makefile │ │ │ ├── lorenz_parameters.cu │ │ │ ├── phase_oscillator_chain.cu │ │ │ ├── phase_oscillator_ensemble.cu │ │ │ └── relaxation.cu │ │ ├── two_dimensional_phase_lattice.cpp │ │ ├── ublas │ │ │ ├── Jamfile.v2 │ │ │ └── lorenz_ublas.cpp │ │ ├── van_der_pol_stiff.cpp │ │ └── vexcl │ │ │ ├── Jamfile.v2 │ │ │ └── lorenz_ensemble.cpp │ │ ├── index.html │ │ ├── performance │ │ ├── Jamfile.v2 │ │ ├── fusion_algebra.hpp │ │ ├── fusion_explicit_error_rk.hpp │ │ ├── fusion_explicit_rk_new.hpp │ │ ├── generic_odeint_rk4_lorenz.cpp │ │ ├── gsl_rk4_lorenz.cpp │ │ ├── lorenz.hpp │ │ ├── lorenz_gsl.hpp │ │ ├── nr_rk4_lorenz.cpp │ │ ├── nr_rk4_phase_lattice.cpp │ │ ├── odeint_rk4_lorenz_array.cpp │ │ ├── odeint_rk4_lorenz_range.cpp │ │ ├── odeint_rk4_phase_lattice.cpp │ │ ├── odeint_rk4_phase_lattice_mkl.cpp │ │ ├── performance.py │ │ ├── phase_lattice.hpp │ │ ├── phase_lattice_mkl.hpp │ │ ├── plot_result.py │ │ ├── rk4_lorenz.f │ │ ├── rk_performance_test_case.hpp │ │ ├── rt_algebra.hpp │ │ ├── rt_explicit_rk.hpp │ │ ├── rt_generic_rk4_lorenz.cpp │ │ └── rt_generic_rk4_phase_lattice.cpp │ │ ├── test │ │ ├── Jamfile.v2 │ │ ├── adams_bashforth.cpp │ │ ├── adams_bashforth_moulton.cpp │ │ ├── adams_moulton.cpp │ │ ├── boost_units_helpers.hpp │ │ ├── bulirsch_stoer.cpp │ │ ├── const_range.hpp │ │ ├── default_operations.cpp │ │ ├── diagnostic_state_type.hpp │ │ ├── dummy_odes.hpp │ │ ├── dummy_steppers.hpp │ │ ├── euler_stepper.cpp │ │ ├── fusion_algebra.cpp │ │ ├── generation.cpp │ │ ├── generic_error_stepper.cpp │ │ ├── generic_stepper.cpp │ │ ├── implicit_euler.cpp │ │ ├── integrate.cpp │ │ ├── integrate_implicit.cpp │ │ ├── integrate_times.cpp │ │ ├── is_pair.cpp │ │ ├── is_resizeable.cpp │ │ ├── numeric │ │ │ ├── Jamfile.v2 │ │ │ ├── rosenbrock.cpp │ │ │ ├── runge_kutta.cpp │ │ │ └── symplectic.cpp │ │ ├── prepare_stepper_testing.hpp │ │ ├── range_algebra.cpp │ │ ├── resize.cpp │ │ ├── resizing.cpp │ │ ├── rosenbrock4.cpp │ │ ├── runge_kutta_concepts.cpp │ │ ├── runge_kutta_controlled_concepts.cpp │ │ ├── runge_kutta_error_concepts.cpp │ │ ├── same_size.cpp │ │ ├── stepper_copying.cpp │ │ ├── stepper_with_ranges.cpp │ │ ├── stepper_with_units.cpp │ │ ├── symplectic_steppers.cpp │ │ ├── trivial_state.cpp │ │ └── vector_space_1d.hpp │ │ └── test_external │ │ ├── gmp │ │ ├── Jamfile.v2 │ │ ├── check_gmp.cpp │ │ └── gmp_integrate.cpp │ │ ├── gsl │ │ ├── Jamfile.v2 │ │ └── check_gsl.cpp │ │ ├── mkl │ │ ├── Jamfile.v2 │ │ └── check_mkl.cpp │ │ ├── mtl4 │ │ ├── Jamfile.v2 │ │ └── mtl4_resize.cpp │ │ ├── thrust │ │ ├── Makefile │ │ └── check_thrust.cu │ │ └── vexcl │ │ ├── Jamfile.v2 │ │ └── lorenz.cpp └── quadrotor_simulator │ └── Quadrotor.h ├── launch └── simulator_example.launch ├── package.xml └── src ├── dynamics └── Quadrotor.cpp ├── quadrotor_simulator_so3.cpp └── test_dynamics └── test_dynamics.cpp /.gitignore: -------------------------------------------------------------------------------- 1 | .vscode/settings.json 2 | .catkin_workspace 3 | build/ 4 | devel/ 5 | files/ 6 | README.md 7 | src/CMakeLists.txt 8 | benchmark_haha.zip 9 | rebound_planner_BB.zip 10 | 11 | -------------------------------------------------------------------------------- /.vscode/c_cpp_properties.json: -------------------------------------------------------------------------------- 1 | { 2 | "configurations": [ 3 | { 4 | "name": "Linux", 5 | "includePath": [ 6 | "${workspaceFolder}/**" 7 | ], 8 | "defines": [], 9 | "compilerPath": "/usr/bin/gcc", 10 | "cStandard": "c11", 11 | "cppStandard": "c++17", 12 | "intelliSenseMode": "clang-x64", 13 | "compileCommands": "${workspaceFolder}/build/compile_commands.json" 14 | } 15 | ], 16 | 17 | "version": 4 18 | } 19 | 20 | -------------------------------------------------------------------------------- /.vscode/tasks.json: -------------------------------------------------------------------------------- 1 | { 2 | "version": "2.0.0", 3 | "tasks": [ 4 | { 5 | "label": "catkin_make", 6 | "type": "shell", 7 | "command": "catkin_make", 8 | "args": ["-DCMAKE_BUILD_TYPE=Release"], 9 | "group": {"kind":"build","isDefault":true}, 10 | "presentation": { 11 | "reveal": "always" 12 | }, 13 | "problemMatcher": "$msCompile" 14 | }, 15 | ] 16 | } 17 | 18 | // catkin_make -DCMAKE_BUILD_TYPE=Release -DCMAKE_EXPORT_COMPILE_COMMANDS=Yes 19 | -------------------------------------------------------------------------------- /modified_realsense2_camera.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/modified_realsense2_camera.zip -------------------------------------------------------------------------------- /pictures/comp.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/pictures/comp.jpg -------------------------------------------------------------------------------- /pictures/indoor.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/pictures/indoor.gif -------------------------------------------------------------------------------- /pictures/outdoor.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/pictures/outdoor.gif -------------------------------------------------------------------------------- /pictures/realsense.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/pictures/realsense.PNG -------------------------------------------------------------------------------- /pictures/sim_demo.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/pictures/sim_demo.gif -------------------------------------------------------------------------------- /pictures/title.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/pictures/title.gif -------------------------------------------------------------------------------- /src/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | /opt/ros/kinetic/share/catkin/cmake/toplevel.cmake -------------------------------------------------------------------------------- /src/planner/bspline_opt/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(bspline_opt) 3 | 4 | set(CMAKE_BUILD_TYPE "Release") 5 | ADD_COMPILE_OPTIONS(-std=c++11 ) 6 | ADD_COMPILE_OPTIONS(-std=c++14 ) 7 | set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g") 8 | 9 | find_package(Eigen3 REQUIRED) 10 | find_package(PCL 1.7 REQUIRED) 11 | 12 | find_package(catkin REQUIRED COMPONENTS 13 | roscpp 14 | rospy 15 | std_msgs 16 | visualization_msgs 17 | plan_env 18 | cv_bridge 19 | path_searching 20 | ) 21 | 22 | catkin_package( 23 | INCLUDE_DIRS include 24 | LIBRARIES bspline_opt 25 | CATKIN_DEPENDS plan_env 26 | # DEPENDS system_lib 27 | ) 28 | 29 | include_directories( 30 | SYSTEM 31 | include 32 | ${catkin_INCLUDE_DIRS} 33 | ${Eigen3_INCLUDE_DIRS} 34 | ${PCL_INCLUDE_DIRS} 35 | ) 36 | 37 | add_library( bspline_opt 38 | src/uniform_bspline.cpp 39 | src/bspline_optimizer.cpp 40 | src/gradient_descent_optimizer.cpp 41 | ) 42 | target_link_libraries( bspline_opt 43 | ${catkin_LIBRARIES} 44 | ) 45 | -------------------------------------------------------------------------------- /src/planner/bspline_opt/include/bspline_opt/gradient_descent_optimizer.h: -------------------------------------------------------------------------------- 1 | #ifndef _GRADIENT_DESCENT_OPT_H_ 2 | #define _GRADIENT_DESCENT_OPT_H_ 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | using namespace std; 9 | 10 | class GradientDescentOptimizer 11 | { 12 | 13 | public: 14 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW; 15 | 16 | typedef double (*objfunDef)(const Eigen::VectorXd &x, Eigen::VectorXd &grad, bool &force_return, void *data); 17 | enum RESULT 18 | { 19 | FIND_MIN, 20 | FAILED, 21 | RETURN_BY_ORDER, 22 | REACH_MAX_ITERATION 23 | }; 24 | 25 | GradientDescentOptimizer(int v_num, objfunDef objf, void *f_data) 26 | { 27 | variable_num_ = v_num; 28 | objfun_ = objf; 29 | f_data_ = f_data; 30 | }; 31 | 32 | void set_maxiter(int limit) { iter_limit_ = limit; } 33 | void set_maxeval(int limit) { invoke_limit_ = limit; } 34 | void set_xtol_rel(double xtol_rel) { xtol_rel_ = xtol_rel; } 35 | void set_xtol_abs(double xtol_abs) { xtol_abs_ = xtol_abs; } 36 | void set_min_grad(double min_grad) { min_grad_ = min_grad; } 37 | 38 | RESULT optimize(Eigen::VectorXd &x_init_optimal, double &opt_f); 39 | 40 | private: 41 | int variable_num_{0}; 42 | int iter_limit_{1e10}; 43 | int invoke_limit_{1e10}; 44 | double xtol_rel_; 45 | double xtol_abs_; 46 | double min_grad_; 47 | double time_limit_; 48 | void *f_data_; 49 | objfunDef objfun_; 50 | }; 51 | 52 | #endif 53 | -------------------------------------------------------------------------------- /src/planner/path_searching/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(path_searching) 3 | 4 | set(CMAKE_BUILD_TYPE "Release") 5 | ADD_COMPILE_OPTIONS(-std=c++11 ) 6 | ADD_COMPILE_OPTIONS(-std=c++14 ) 7 | set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g") 8 | 9 | find_package(Eigen3 REQUIRED) 10 | find_package(PCL 1.7 REQUIRED) 11 | 12 | find_package(catkin REQUIRED COMPONENTS 13 | roscpp 14 | rospy 15 | std_msgs 16 | visualization_msgs 17 | plan_env 18 | cv_bridge 19 | ) 20 | 21 | 22 | catkin_package( 23 | INCLUDE_DIRS include 24 | LIBRARIES path_searching 25 | CATKIN_DEPENDS plan_env 26 | # DEPENDS system_lib 27 | ) 28 | 29 | include_directories( 30 | SYSTEM 31 | include 32 | ${catkin_INCLUDE_DIRS} 33 | ${Eigen3_INCLUDE_DIRS} 34 | ${PCL_INCLUDE_DIRS} 35 | ) 36 | 37 | add_library( path_searching 38 | src/dyn_a_star.cpp 39 | ) 40 | target_link_libraries( path_searching 41 | ${catkin_LIBRARIES} 42 | ) 43 | -------------------------------------------------------------------------------- /src/planner/plan_env/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(plan_env) 3 | 4 | set(CMAKE_BUILD_TYPE "Release") 5 | ADD_COMPILE_OPTIONS(-std=c++11 ) 6 | ADD_COMPILE_OPTIONS(-std=c++14 ) 7 | set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g") 8 | 9 | find_package(OpenCV REQUIRED) 10 | 11 | 12 | find_package(catkin REQUIRED COMPONENTS 13 | roscpp 14 | rospy 15 | std_msgs 16 | visualization_msgs 17 | cv_bridge 18 | message_filters 19 | ) 20 | 21 | find_package(Eigen3 REQUIRED) 22 | find_package(PCL 1.7 REQUIRED) 23 | 24 | catkin_package( 25 | INCLUDE_DIRS include 26 | LIBRARIES plan_env 27 | CATKIN_DEPENDS roscpp std_msgs 28 | # DEPENDS system_lib 29 | ) 30 | 31 | include_directories( 32 | SYSTEM 33 | include 34 | ${catkin_INCLUDE_DIRS} 35 | ${Eigen3_INCLUDE_DIRS} 36 | ${PCL_INCLUDE_DIRS} 37 | ${OpenCV_INCLUDE_DIRS} 38 | ) 39 | 40 | link_directories(${PCL_LIBRARY_DIRS}) 41 | 42 | add_library( plan_env 43 | src/grid_map.cpp 44 | src/raycast.cpp 45 | ) 46 | target_link_libraries( plan_env 47 | ${catkin_LIBRARIES} 48 | ${PCL_LIBRARIES} 49 | ) 50 | -------------------------------------------------------------------------------- /src/planner/plan_env/include/plan_env/raycast.h: -------------------------------------------------------------------------------- 1 | #ifndef RAYCAST_H_ 2 | #define RAYCAST_H_ 3 | 4 | #include 5 | #include 6 | 7 | double signum(double x); 8 | 9 | double mod(double value, double modulus); 10 | 11 | double intbound(double s, double ds); 12 | 13 | void Raycast(const Eigen::Vector3d& start, const Eigen::Vector3d& end, const Eigen::Vector3d& min, 14 | const Eigen::Vector3d& max, int& output_points_cnt, Eigen::Vector3d* output); 15 | 16 | void Raycast(const Eigen::Vector3d& start, const Eigen::Vector3d& end, const Eigen::Vector3d& min, 17 | const Eigen::Vector3d& max, std::vector* output); 18 | 19 | class RayCaster { 20 | private: 21 | /* data */ 22 | Eigen::Vector3d start_; 23 | Eigen::Vector3d end_; 24 | Eigen::Vector3d direction_; 25 | Eigen::Vector3d min_; 26 | Eigen::Vector3d max_; 27 | int x_; 28 | int y_; 29 | int z_; 30 | int endX_; 31 | int endY_; 32 | int endZ_; 33 | double maxDist_; 34 | double dx_; 35 | double dy_; 36 | double dz_; 37 | int stepX_; 38 | int stepY_; 39 | int stepZ_; 40 | double tMaxX_; 41 | double tMaxY_; 42 | double tMaxZ_; 43 | double tDeltaX_; 44 | double tDeltaY_; 45 | double tDeltaZ_; 46 | double dist_; 47 | 48 | int step_num_; 49 | 50 | public: 51 | RayCaster(/* args */) { 52 | } 53 | ~RayCaster() { 54 | } 55 | 56 | bool setInput(const Eigen::Vector3d& start, 57 | const Eigen::Vector3d& end /* , const Eigen::Vector3d& min, 58 | const Eigen::Vector3d& max */); 59 | 60 | bool step(Eigen::Vector3d& ray_pt); 61 | }; 62 | 63 | #endif // RAYCAST_H_ -------------------------------------------------------------------------------- /src/planner/plan_manage/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(ego_planner) 3 | 4 | set(CMAKE_BUILD_TYPE "Release") 5 | ADD_COMPILE_OPTIONS(-std=c++11 ) 6 | ADD_COMPILE_OPTIONS(-std=c++14 ) 7 | set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g") 8 | 9 | find_package(Eigen3 REQUIRED) 10 | find_package(PCL 1.7 REQUIRED) 11 | 12 | find_package(catkin REQUIRED COMPONENTS 13 | roscpp 14 | std_msgs 15 | geometry_msgs 16 | quadrotor_msgs 17 | plan_env 18 | path_searching 19 | bspline_opt 20 | traj_utils 21 | message_generation 22 | cv_bridge 23 | ) 24 | 25 | # Generate messages in the 'msg' folder 26 | add_message_files( 27 | FILES 28 | Bspline.msg 29 | DataDisp.msg 30 | ) 31 | 32 | # Generate added messages and services with any dependencies listed here 33 | generate_messages( 34 | DEPENDENCIES 35 | std_msgs 36 | geometry_msgs 37 | ) 38 | 39 | # catkin_package(CATKIN_DEPENDS message_runtime) 40 | catkin_package( 41 | INCLUDE_DIRS include 42 | LIBRARIES ego_planner 43 | CATKIN_DEPENDS plan_env path_searching bspline_opt traj_utils message_runtime 44 | # DEPENDS system_lib 45 | ) 46 | 47 | include_directories( 48 | include 49 | SYSTEM 50 | ${catkin_INCLUDE_DIRS} ${PROJECT_SOURCE_DIR}/include 51 | ${EIGEN3_INCLUDE_DIR} 52 | ${PCL_INCLUDE_DIRS} 53 | ) 54 | 55 | 56 | add_executable(ego_planner_node 57 | src/ego_planner_node.cpp 58 | src/ego_replan_fsm.cpp 59 | src/planner_manager.cpp 60 | ) 61 | target_link_libraries(ego_planner_node 62 | ${catkin_LIBRARIES} 63 | ) 64 | add_dependencies(ego_planner_node ${${PROJECT_NAME}_EXPORTED_TARGETS}) 65 | 66 | add_executable(traj_server src/traj_server.cpp) 67 | target_link_libraries(traj_server ${catkin_LIBRARIES}) 68 | add_dependencies(traj_server ${${PROJECT_NAME}_EXPORTED_TARGETS}) 69 | 70 | 71 | -------------------------------------------------------------------------------- /src/planner/plan_manage/launch/rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /src/planner/plan_manage/msg/Bspline.msg: -------------------------------------------------------------------------------- 1 | int32 order 2 | int64 traj_id 3 | time start_time 4 | 5 | float64[] knots 6 | geometry_msgs/Point[] pos_pts 7 | 8 | float64[] yaw_pts 9 | float64 yaw_dt 10 | 11 | -------------------------------------------------------------------------------- /src/planner/plan_manage/msg/DataDisp.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | float64 a 4 | float64 b 5 | float64 c 6 | float64 d 7 | float64 e -------------------------------------------------------------------------------- /src/planner/plan_manage/src/ego_planner_node.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | #include 5 | 6 | using namespace ego_planner; 7 | 8 | int main(int argc, char **argv) 9 | { 10 | ros::init(argc, argv, "ego_planner_node"); 11 | ros::NodeHandle nh("~"); 12 | 13 | EGOReplanFSM rebo_replan; 14 | 15 | rebo_replan.init(nh); 16 | 17 | ros::Duration(1.0).sleep(); 18 | ros::spin(); 19 | 20 | return 0; 21 | } 22 | -------------------------------------------------------------------------------- /src/planner/traj_utils/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(traj_utils) 3 | 4 | set(CMAKE_BUILD_TYPE "Release") 5 | set(CMAKE_CXX_FLAGS "-std=c++11") 6 | set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g") 7 | 8 | find_package(catkin REQUIRED COMPONENTS 9 | bspline_opt 10 | path_searching 11 | roscpp 12 | std_msgs 13 | cv_bridge 14 | ) 15 | 16 | find_package(Eigen3 REQUIRED) 17 | find_package(PCL 1.7 REQUIRED) 18 | 19 | catkin_package( 20 | INCLUDE_DIRS include 21 | LIBRARIES traj_utils 22 | CATKIN_DEPENDS path_searching bspline_opt 23 | # DEPENDS system_lib 24 | ) 25 | 26 | include_directories( 27 | SYSTEM 28 | include 29 | ${catkin_INCLUDE_DIRS} 30 | ${Eigen3_INCLUDE_DIRS} 31 | ${PCL_INCLUDE_DIRS} 32 | ) 33 | 34 | link_directories(${PCL_LIBRARY_DIRS}) 35 | 36 | add_library( traj_utils 37 | src/planning_visualization.cpp 38 | src/polynomial_traj.cpp 39 | ) 40 | target_link_libraries( traj_utils 41 | ${catkin_LIBRARIES} 42 | ) 43 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/cmake_utils/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(cmake_utils) 3 | 4 | find_package(catkin REQUIRED COMPONENTS roscpp) 5 | 6 | set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/cmake) 7 | 8 | file(GLOB CMAKE_UILTS_FILES cmake/*.cmake) 9 | 10 | catkin_package( 11 | CFG_EXTRAS ${CMAKE_UILTS_FILES} 12 | ) 13 | 14 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/cmake_utils/cmake/cmake_modules.cmake: -------------------------------------------------------------------------------- 1 | list(APPEND CMAKE_MODULE_PATH "${cmake_utils_SOURCE_PREFIX}/cmake_modules") 2 | link_directories( ${cmake_utils_SOURCE_PREFIX}/lib/mosek8 ) 3 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/cmake_utils/cmake/color.cmake: -------------------------------------------------------------------------------- 1 | string(ASCII 27 Esc) 2 | set(ColourReset "${Esc}[m") 3 | set(ColourBold "${Esc}[1m") 4 | set(Red "${Esc}[31m") 5 | set(Green "${Esc}[32m") 6 | set(Yellow "${Esc}[33m") 7 | set(Blue "${Esc}[34m") 8 | set(Magenta "${Esc}[35m") 9 | set(Cyan "${Esc}[36m") 10 | set(White "${Esc}[37m") 11 | set(BoldRed "${Esc}[1;31m") 12 | set(BoldGreen "${Esc}[1;32m") 13 | set(BoldYellow "${Esc}[1;33m") 14 | set(BoldBlue "${Esc}[1;34m") 15 | set(BoldMagenta "${Esc}[1;35m") 16 | set(BoldCyan "${Esc}[1;36m") 17 | set(BoldWhite "${Esc}[1;37m") 18 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/cmake_utils/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | cmake_utils 4 | 0.0.0 5 | 6 | Once you used this package, 7 | then you do not need to copy cmake files among packages 8 | 9 | 10 | William.Wu 11 | 12 | LGPLv3 13 | 14 | catkin 15 | roscpp 16 | cmake_modules 17 | 18 | 19 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/multi_map_server/Makefile: -------------------------------------------------------------------------------- 1 | include $(shell rospack find mk)/cmake.mk -------------------------------------------------------------------------------- /src/uav_simulator/Utils/multi_map_server/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b multi_map_server is ... 6 | 7 | 10 | 11 | 12 | \section codeapi Code API 13 | 14 | 24 | 25 | 26 | */ 27 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/multi_map_server/msg/MultiOccupancyGrid.msg: -------------------------------------------------------------------------------- 1 | nav_msgs/OccupancyGrid[] maps 2 | geometry_msgs/Pose[] origins 3 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/multi_map_server/msg/MultiSparseMap3D.msg: -------------------------------------------------------------------------------- 1 | SparseMap3D[] maps 2 | geometry_msgs/Pose[] origins 3 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/multi_map_server/msg/SparseMap3D.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | nav_msgs/MapMetaData info 3 | VerticalOccupancyGridList[] lists 4 | 5 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/multi_map_server/msg/VerticalOccupancyGridList.msg: -------------------------------------------------------------------------------- 1 | float32 x 2 | float32 y 3 | int32[] upper 4 | int32[] lower 5 | int32[] mass 6 | 7 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/multi_map_server/package.xml: -------------------------------------------------------------------------------- 1 | 2 | multi_map_server 3 | multi_map_server 4 | 0.0.0 5 | Shaojie Shen 6 | BSD 7 | 8 | http://ros.org/wiki/multi_map_server 9 | 10 | catkin 11 | 12 | roscpp 13 | visualization_msgs 14 | geometry_msgs 15 | tf 16 | nav_msgs 17 | std_srvs 18 | laser_geometry 19 | pose_utils 20 | message_generation 21 | quadrotor_msgs 22 | 23 | roscpp 24 | visualization_msgs 25 | geometry_msgs 26 | tf 27 | nav_msgs 28 | std_srvs 29 | laser_geometry 30 | pose_utils 31 | message_runtime 32 | quadrotor_msgs 33 | 34 | 35 | 36 | 37 | 38 | 39 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/multi_map_server/src/multi_map_server/__init__.py: -------------------------------------------------------------------------------- 1 | #autogenerated by ROS python message generators -------------------------------------------------------------------------------- /src/uav_simulator/Utils/multi_map_server/src/multi_map_server/msg/__init__.py: -------------------------------------------------------------------------------- 1 | from ._SparseMap3D import * 2 | from ._MultiOccupancyGrid import * 3 | from ._MultiSparseMap3D import * 4 | from ._VerticalOccupancyGridList import * 5 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/odom_visualization/Makefile: -------------------------------------------------------------------------------- 1 | include $(shell rospack find mk)/cmake.mk -------------------------------------------------------------------------------- /src/uav_simulator/Utils/odom_visualization/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b odom_visualization is ... 6 | 7 | 10 | 11 | 12 | \section codeapi Code API 13 | 14 | 24 | 25 | 26 | */ 27 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/odom_visualization/meshes/hummingbird.mesh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/Utils/odom_visualization/meshes/hummingbird.mesh -------------------------------------------------------------------------------- /src/uav_simulator/Utils/odom_visualization/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 0.0.0 3 | odom_visualization 4 | 5 | 6 | odom_visualization 7 | 8 | 9 | Shaojie Shen 10 | BSD 11 | http://ros.org/wiki/odom_visualization 12 | 13 | catkin 14 | 15 | roscpp 16 | sensor_msgs 17 | nav_msgs 18 | visualization_msgs 19 | tf 20 | pose_utils 21 | 22 | roscpp 23 | sensor_msgs 24 | nav_msgs 25 | visualization_msgs 26 | tf 27 | pose_utils 28 | 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/pose_utils/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(pose_utils) 3 | 4 | find_package(catkin REQUIRED COMPONENTS 5 | #armadillo 6 | roscpp 7 | ) 8 | 9 | catkin_package( 10 | INCLUDE_DIRS include 11 | LIBRARIES pose_utils 12 | # CATKIN_DEPENDS geometry_msgs nav_msgs 13 | # DEPENDS system_lib 14 | ) 15 | 16 | find_package(Armadillo REQUIRED) 17 | 18 | include_directories( 19 | ${catkin_INCLUDE_DIRS} 20 | ${ARMADILLO_INCLUDE_DIRS} 21 | include 22 | ) 23 | 24 | add_library(pose_utils 25 | ${ARMADILLO_LIBRARIES} 26 | src/pose_utils.cpp) 27 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/pose_utils/Makefile: -------------------------------------------------------------------------------- 1 | include $(shell rospack find mk)/cmake.mk -------------------------------------------------------------------------------- /src/uav_simulator/Utils/pose_utils/include/pose_utils.h: -------------------------------------------------------------------------------- 1 | #ifndef POSE_UTILS_H 2 | #define POSE_UTILS_H 3 | 4 | #include 5 | #include "armadillo" 6 | 7 | #define PI 3.14159265359 8 | #define NUM_INF 999999.9 9 | 10 | using namespace arma; 11 | using namespace std; 12 | 13 | // Rotation --------------------- 14 | mat ypr_to_R(const colvec& ypr); 15 | 16 | mat yaw_to_R(double yaw); 17 | 18 | colvec R_to_ypr(const mat& R); 19 | 20 | mat quaternion_to_R(const colvec& q); 21 | 22 | colvec R_to_quaternion(const mat& R); 23 | 24 | colvec quaternion_mul(const colvec& q1, const colvec& q2); 25 | 26 | colvec quaternion_inv(const colvec& q); 27 | 28 | // General Pose Update ---------- 29 | colvec pose_update(const colvec& X1, const colvec& X2); 30 | 31 | colvec pose_inverse(const colvec& X); 32 | 33 | colvec pose_update_2d(const colvec& X1, const colvec& X2); 34 | 35 | colvec pose_inverse_2d(const colvec& X); 36 | 37 | // For Pose EKF ----------------- 38 | mat Jplus1(const colvec& X1, const colvec& X2); 39 | 40 | mat Jplus2(const colvec& X1, const colvec& X2); 41 | 42 | // For IMU EKF ------------------ 43 | colvec state_update(const colvec& X, const colvec& U, double dt); 44 | 45 | mat jacobianF(const colvec& X, const colvec& U, double dt); 46 | 47 | mat jacobianU(const colvec& X, const colvec& U, double dt); 48 | 49 | colvec state_measure(const colvec& X); 50 | 51 | mat jacobianH(); 52 | 53 | #endif 54 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/pose_utils/package.xml: -------------------------------------------------------------------------------- 1 | 2 | pose_utils 3 | 0.0.0 4 | pose_utils 5 | Shaojie Shen 6 | BSD 7 | catkin 8 | roscpp 9 | roscpp 10 | 11 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/include/quadrotor_msgs/decode_msgs.h: -------------------------------------------------------------------------------- 1 | #ifndef __QUADROTOR_MSGS_QUADROTOR_MSGS_H__ 2 | #define __QUADROTOR_MSGS_QUADROTOR_MSGS_H__ 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | namespace quadrotor_msgs 11 | { 12 | 13 | bool decodeOutputData(const std::vector &data, 14 | quadrotor_msgs::OutputData &output); 15 | 16 | bool decodeStatusData(const std::vector &data, 17 | quadrotor_msgs::StatusData &status); 18 | 19 | bool decodePPROutputData(const std::vector &data, 20 | quadrotor_msgs::PPROutputData &output); 21 | } 22 | 23 | #endif 24 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/include/quadrotor_msgs/encode_msgs.h: -------------------------------------------------------------------------------- 1 | #ifndef __QUADROTOR_MSGS_QUADROTOR_MSGS_H__ 2 | #define __QUADROTOR_MSGS_QUADROTOR_MSGS_H__ 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | namespace quadrotor_msgs 11 | { 12 | 13 | void encodeSO3Command(const quadrotor_msgs::SO3Command &so3_command, 14 | std::vector &output); 15 | void encodeTRPYCommand(const quadrotor_msgs::TRPYCommand &trpy_command, 16 | std::vector &output); 17 | 18 | void encodePPRGains(const quadrotor_msgs::Gains &gains, 19 | std::vector &output); 20 | } 21 | 22 | #endif 23 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/AuxCommand.msg: -------------------------------------------------------------------------------- 1 | float64 current_yaw 2 | float64 kf_correction 3 | float64[2] angle_corrections# Trims for roll, pitch 4 | bool enable_motors 5 | bool use_external_yaw 6 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/Corrections.msg: -------------------------------------------------------------------------------- 1 | float64 kf_correction 2 | float64[2] angle_corrections 3 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/Gains.msg: -------------------------------------------------------------------------------- 1 | float64 Kp 2 | float64 Kd 3 | float64 Kp_yaw 4 | float64 Kd_yaw 5 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/LQRTrajectory.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # the trajectory id, starts from "1". 4 | uint32 trajectory_id 5 | 6 | # the action command for trajectory server. 7 | uint32 ACTION_ADD = 1 8 | uint32 ACTION_ABORT = 2 9 | uint32 ACTION_WARN_START = 3 10 | uint32 ACTION_WARN_FINAL = 4 11 | uint32 ACTION_WARN_IMPOSSIBLE = 5 12 | uint32 action 13 | 14 | # the weight coefficient of the control effort 15 | float64 r 16 | 17 | # the yaw command 18 | float64 start_yaw 19 | float64 final_yaw 20 | 21 | # the initial and final state 22 | float64[6] s0 23 | float64[3] ut 24 | 25 | float64[6] sf 26 | 27 | # the optimal arrival time 28 | float64 t_f 29 | 30 | string debug_info 31 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/Odometry.msg: -------------------------------------------------------------------------------- 1 | uint8 STATUS_ODOM_VALID=0 2 | uint8 STATUS_ODOM_INVALID=1 3 | uint8 STATUS_ODOM_LOOPCLOSURE=2 4 | 5 | nav_msgs/Odometry curodom 6 | nav_msgs/Odometry kfodom 7 | uint32 kfid 8 | uint8 status 9 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/OutputData.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint16 loop_rate 3 | float64 voltage 4 | geometry_msgs/Quaternion orientation 5 | geometry_msgs/Vector3 angular_velocity 6 | geometry_msgs/Vector3 linear_acceleration 7 | float64 pressure_dheight 8 | float64 pressure_height 9 | geometry_msgs/Vector3 magnetic_field 10 | uint8[8] radio_channel 11 | #uint8[4] motor_rpm 12 | uint8 seq 13 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/PPROutputData.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint16 quad_time 3 | float64 des_thrust 4 | float64 des_roll 5 | float64 des_pitch 6 | float64 des_yaw 7 | float64 est_roll 8 | float64 est_pitch 9 | float64 est_yaw 10 | float64 est_angvel_x 11 | float64 est_angvel_y 12 | float64 est_angvel_z 13 | float64 est_acc_x 14 | float64 est_acc_y 15 | float64 est_acc_z 16 | uint16[4] pwm 17 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/PolynomialTrajectory.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # the trajectory id, starts from "1". 4 | uint32 trajectory_id 5 | 6 | # the action command for trajectory server. 7 | uint32 ACTION_ADD = 1 8 | uint32 ACTION_ABORT = 2 9 | uint32 ACTION_WARN_START = 3 10 | uint32 ACTION_WARN_FINAL = 4 11 | uint32 ACTION_WARN_IMPOSSIBLE = 5 12 | uint32 action 13 | 14 | # the order of trajectory. 15 | uint32 num_order 16 | uint32 num_segment 17 | 18 | # the polynomial coecfficients of the trajectory. 19 | float64 start_yaw 20 | float64 final_yaw 21 | float64[] coef_x 22 | float64[] coef_y 23 | float64[] coef_z 24 | float64[] time 25 | float64 mag_coeff 26 | uint32[] order 27 | 28 | string debug_info 29 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/PolynomialTrajectory.msg~: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # the trajectory id, starts from "1". 4 | uint32 trajectory_id 5 | 6 | # the action command for trajectory server. 7 | uint32 ACTION_ADD = 1 8 | uint32 ACTION_ABORT = 2 9 | uint32 ACTION_WARN_START = 3 10 | uint32 ACTION_WARN_FINAL = 4 11 | uint32 ACTION_WARN_IMPOSSIBLE = 5 12 | uint32 action 13 | 14 | # the order of trajectory. 15 | uint32 num_order 16 | uint32 num_segment 17 | 18 | # the polynomial coecfficients of the trajectory. 19 | float64 start_yaw 20 | float64 final_yaw 21 | float64[] coef_x 22 | float64[] coef_y 23 | float64[] coef_z 24 | float64[] time 25 | float64 mag_coeff 26 | string debug_info 27 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/PositionCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | geometry_msgs/Point position 3 | geometry_msgs/Vector3 velocity 4 | geometry_msgs/Vector3 acceleration 5 | float64 yaw 6 | float64 yaw_dot 7 | float64[3] kx 8 | float64[3] kv 9 | 10 | uint32 trajectory_id 11 | 12 | uint8 TRAJECTORY_STATUS_EMPTY = 0 13 | uint8 TRAJECTORY_STATUS_READY = 1 14 | uint8 TRAJECTORY_STATUS_COMPLETED = 3 15 | uint8 TRAJECTROY_STATUS_ABORT = 4 16 | uint8 TRAJECTORY_STATUS_ILLEGAL_START = 5 17 | uint8 TRAJECTORY_STATUS_ILLEGAL_FINAL = 6 18 | uint8 TRAJECTORY_STATUS_IMPOSSIBLE = 7 19 | 20 | # Its ID number will start from 1, allowing you comparing it with 0. 21 | uint8 trajectory_flag 22 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/PositionCommand.msg~: -------------------------------------------------------------------------------- 1 | Header header 2 | geometry_msgs/Point position 3 | geometry_msgs/Vector3 velocity 4 | geometry_msgs/Vector3 acceleration 5 | float64 yaw 6 | float64 yaw_dot 7 | float64[3] kx 8 | float64[3] kv 9 | 10 | uint32 trajectory_id 11 | 12 | uint8 TRAJECTORY_STATUS_EMPTY = 0 13 | uint8 TRAJECTORY_STATUS_READY = 1 14 | uint8 TRAJECTORY_STATUS_COMPLETE = 3 15 | uint8 TRAJECTROY_STATUS_ABORT = 8 16 | 17 | uint8 trajectory_flag 18 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/SO3Command.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | geometry_msgs/Vector3 force 3 | geometry_msgs/Quaternion orientation 4 | float64[3] kR 5 | float64[3] kOm 6 | quadrotor_msgs/AuxCommand aux 7 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/Serial.msg: -------------------------------------------------------------------------------- 1 | # Note: These constants need to be kept in sync with the types 2 | # defined in include/quadrotor_msgs/comm_types.h 3 | uint8 SO3_CMD = 115 # 's' in base 10 4 | uint8 TRPY_CMD = 112 # 'p' in base 10 5 | uint8 STATUS_DATA = 99 # 'c' in base 10 6 | uint8 OUTPUT_DATA = 100 # 'd' in base 10 7 | uint8 PPR_OUTPUT_DATA = 116 # 't' in base 10 8 | uint8 PPR_GAINS = 103 # 'g' 9 | 10 | Header header 11 | uint8 channel 12 | uint8 type # One of the types listed above 13 | uint8[] data 14 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/StatusData.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint16 loop_rate 3 | float64 voltage 4 | uint8 seq 5 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/msg/TRPYCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 thrust 3 | float32 roll 4 | float32 pitch 5 | float32 yaw 6 | quadrotor_msgs/AuxCommand aux 7 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | quadrotor_msgs 3 | 0.0.0 4 | quadrotor_msgs 5 | Kartik Mohta 6 | http://ros.org/wiki/quadrotor_msgs 7 | BSD 8 | catkin 9 | geometry_msgs 10 | nav_msgs 11 | message_generation 12 | geometry_msgs 13 | nav_msgs 14 | message_runtime 15 | 16 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/src/quadrotor_msgs/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/Utils/quadrotor_msgs/src/quadrotor_msgs/__init__.py -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/src/quadrotor_msgs/__init__.pyc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/Utils/quadrotor_msgs/src/quadrotor_msgs/__init__.pyc -------------------------------------------------------------------------------- /src/uav_simulator/Utils/quadrotor_msgs/src/quadrotor_msgs/msg/__init__.py: -------------------------------------------------------------------------------- 1 | from ._Gains import * 2 | from ._SO3Command import * 3 | from ._TRPYCommand import * 4 | from ._PositionCommand import * 5 | from ._PPROutputData import * 6 | from ._OutputData import * 7 | from ._Corrections import * 8 | from ._Serial import * 9 | from ._AuxCommand import * 10 | from ._StatusData import * 11 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/rviz_plugins/package.xml: -------------------------------------------------------------------------------- 1 | 2 | rviz_plugins 3 | 4 | 5 | Additional plugins for rviz 6 | 7 | 8 | 0.1.0 9 | Shaojie Shen 10 | william.wu 11 | LGPLv3 12 | http://ros.org/wiki/rviz_plugins 13 | 14 | catkin 15 | 16 | rviz 17 | roscpp 18 | multi_map_server 19 | qtbase5-dev 20 | message_runtime 21 | 22 | rviz 23 | multi_map_server 24 | message_runtime 25 | roscpp 26 | libqt5-core 27 | libqt5-gui 28 | libqt5-widgets 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/rviz_plugins/plugin_description.xml: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | Tool for setting 3D goal 7 | 8 | 9 | 10 | 13 | 14 | Display of -inf +inf probabilistic occupancy grid map 15 | 16 | 17 | 18 | 21 | 22 | game usage 23 | 24 | 25 | 26 | 29 | 30 | Display of aerial map 31 | 32 | 33 | 34 | 37 | 38 | Display of multiple -inf +inf probabilistic occupancy grid map 39 | 40 | 41 | 42 | 43 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/uav_utils/include/uav_utils/utils.h: -------------------------------------------------------------------------------- 1 | #ifndef __UAV_UTILS_H 2 | #define __UAV_UTILS_H 3 | 4 | #include 5 | 6 | #include 7 | #include 8 | 9 | namespace uav_utils 10 | { 11 | 12 | /* judge if value belongs to [low,high] */ 13 | template 14 | bool 15 | in_range(T value, const T2& low, const T2& high) 16 | { 17 | ROS_ASSERT_MSG(low < high, "%f < %f?", low, high); 18 | return (low <= value) && (value <= high); 19 | } 20 | 21 | /* judge if value belongs to [-limit, limit] */ 22 | template 23 | bool 24 | in_range(T value, const T2& limit) 25 | { 26 | ROS_ASSERT_MSG(limit > 0, "%f > 0?", limit); 27 | return in_range(value, -limit, limit); 28 | } 29 | 30 | template 31 | void 32 | limit_range(T& value, const T2& low, const T2& high) 33 | { 34 | ROS_ASSERT_MSG(low < high, "%f < %f?", low, high); 35 | if (value < low) 36 | { 37 | value = low; 38 | } 39 | 40 | if (value > high) 41 | { 42 | value = high; 43 | } 44 | 45 | return; 46 | } 47 | 48 | template 49 | void 50 | limit_range(T& value, const T2& limit) 51 | { 52 | ROS_ASSERT_MSG(limit > 0, "%f > 0?", limit); 53 | limit_range(value, -limit, limit); 54 | } 55 | 56 | typedef std::stringstream DebugSS_t; 57 | } // end of namespace uav_utils 58 | 59 | #endif 60 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/uav_utils/scripts/send_odom.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | import rospy 4 | import numpy as np 5 | import tf 6 | from tf import transformations as tfs 7 | from nav_msgs.msg import Odometry 8 | 9 | if __name__ == "__main__": 10 | rospy.init_node("odom_sender") 11 | 12 | msg = Odometry() 13 | 14 | msg.header.stamp = rospy.Time.now()-rospy.Duration(0.2) 15 | msg.header.frame_id = "world" 16 | 17 | q = tfs.quaternion_from_euler(0,0,0,"rzyx") 18 | 19 | msg.pose.pose.position.x = 0 20 | msg.pose.pose.position.y = 0 21 | msg.pose.pose.position.z = 0 22 | msg.twist.twist.linear.x = 0 23 | msg.twist.twist.linear.y = 0 24 | msg.twist.twist.linear.z = 0 25 | msg.pose.pose.orientation.x = q[0] 26 | msg.pose.pose.orientation.y = q[1] 27 | msg.pose.pose.orientation.z = q[2] 28 | msg.pose.pose.orientation.w = q[3] 29 | 30 | print(msg) 31 | 32 | pub = rospy.Publisher("odom", Odometry, queue_size=10) 33 | 34 | counter = 0 35 | r = rospy.Rate(1) 36 | 37 | while not rospy.is_shutdown(): 38 | counter += 1 39 | msg.header.stamp = rospy.Time.now()-rospy.Duration(0.2) 40 | pub.publish(msg) 41 | rospy.loginfo("Send %3d msg(s)."%counter) 42 | r.sleep() 43 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/uav_utils/scripts/topic_statistics.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | import argparse as ap 4 | import argcomplete 5 | 6 | def main(**args): 7 | pass 8 | 9 | if __name__ == '__main__': 10 | parser = ap.ArgumentParser() 11 | parser.add_argument('positional', choices=['spam', 'eggs']) 12 | parser.add_argument('--optional', choices=['foo1', 'foo2', 'bar']) 13 | argcomplete.autocomplete(parser) 14 | args = parser.parse_args() 15 | main(**vars(args)) -------------------------------------------------------------------------------- /src/uav_simulator/Utils/waypoint_generator/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(waypoint_generator) 3 | 4 | set(CMAKE_VERBOSE_MAKEFILE "false") 5 | include(CheckCXXCompilerFlag) 6 | CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) 7 | CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) 8 | if(COMPILER_SUPPORTS_CXX11) 9 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") 10 | elseif(COMPILER_SUPPORTS_CXX0X) 11 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") 12 | else() 13 | message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.") 14 | endif() 15 | 16 | set(ADDITIONAL_CXX_FLAG "-Wall -O3 -march=native") 17 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${ADDITIONAL_CXX_FLAG}") 18 | 19 | find_package(catkin REQUIRED COMPONENTS 20 | roscpp 21 | tf 22 | nav_msgs 23 | ) 24 | catkin_package() 25 | 26 | include_directories(include) 27 | include_directories( 28 | ${catkin_INCLUDE_DIRS} 29 | ) 30 | 31 | add_executable(waypoint_generator src/waypoint_generator.cpp) 32 | 33 | target_link_libraries(waypoint_generator 34 | ${catkin_LIBRARIES} 35 | ) 36 | -------------------------------------------------------------------------------- /src/uav_simulator/Utils/waypoint_generator/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 0.0.0 3 | waypoint_generator 4 | 5 | 6 | waypoint_generator 7 | 8 | 9 | Shaojie Shen 10 | BSD 11 | http://ros.org/wiki/waypoint_generator 12 | 13 | catkin 14 | 15 | roscpp 16 | tf 17 | nav_msgs 18 | 19 | roscpp 20 | tf 21 | nav_msgs 22 | 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /src/uav_simulator/local_sensing/.vscode/settings.json: -------------------------------------------------------------------------------- 1 | { 2 | "files.associations": { 3 | "*.cuh": "cpp" 4 | } 5 | } -------------------------------------------------------------------------------- /src/uav_simulator/local_sensing/cfg/local_sensing_node.cfg: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | PACKAGE = "local_sensing_node" 3 | 4 | from dynamic_reconfigure.parameter_generator_catkin import * 5 | 6 | gen = ParameterGenerator() 7 | 8 | gen.add("tx", double_t, 0, "tx", 0.0, -1000.0, 1000.0) 9 | gen.add("ty", double_t, 0, "ty", 0.0, -1000.0, 1000.0) 10 | gen.add("tz", double_t, 0, "tz", 0.0, -1000.0, 1000.0) 11 | gen.add("axis_x", double_t, 0, "axis_x", 0.0, -360.0, 360.0) 12 | gen.add("axis_y", double_t, 0, "axis_y", 0.0, -360.0, 360.0) 13 | gen.add("axis_z", double_t, 0, "axis_z", 0.0, -360.0, 360.0) 14 | 15 | exit(gen.generate(PACKAGE, "local_sensing_node", "local_sensing_node")) -------------------------------------------------------------------------------- /src/uav_simulator/local_sensing/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | local_sensing_node 4 | 0.1.0 5 | 6 | render depth from depth 7 | 8 | Matia Pizzoli 9 | Matia Pizzoli 10 | GPLv3 11 | 12 | 13 | catkin 14 | 15 | 16 | cmake_modules 17 | roscpp 18 | roslib 19 | svo_msgs 20 | cv_bridge 21 | image_transport 22 | vikit_ros 23 | pcl_ros 24 | dynamic_reconfigure 25 | quadrotor_msgs 26 | 27 | 28 | roscpp 29 | roslib 30 | svo_msgs 31 | cv_bridge 32 | image_transport 33 | vikit_ros 34 | pcl_ros 35 | dynamic_reconfigure 36 | quadrotor_msgs 37 | 38 | 39 | -------------------------------------------------------------------------------- /src/uav_simulator/local_sensing/params/camera.yaml: -------------------------------------------------------------------------------- 1 | cam_width: 640 2 | cam_height: 480 3 | cam_fx: 387.229248046875 4 | cam_fy: 387.229248046875 5 | cam_cx: 321.04638671875 6 | cam_cy: 243.44969177246094 7 | -------------------------------------------------------------------------------- /src/uav_simulator/local_sensing/src/csv_convert.py: -------------------------------------------------------------------------------- 1 | import csv 2 | file_location = '/home/wang/bag/banchmark/EuRoC/ViconRoom101/state_groundtruth_estimate0/data.csv' 3 | with open('/home/wang/bag/banchmark/EuRoC/ViconRoom101/state_groundtruth_estimate0/data.txt', 'w') as txt_f: 4 | with open(file_location) as f: 5 | f_csv = csv.reader(f) 6 | headers = next(f_csv) 7 | for row in f_csv: 8 | txt_f.write('%lf\n'% (float(row[0]) / 1000000000.0) ) 9 | txt_f.write('%lf\n'% (float(row[1])) ) 10 | txt_f.write('%lf\n'% (float(row[2])) ) 11 | txt_f.write('%lf\n'% (float(row[3])) ) 12 | txt_f.write('%lf\n'% (float(row[4])) ) 13 | txt_f.write('%lf\n'% (float(row[5])) ) 14 | txt_f.write('%lf\n'% (float(row[6])) ) 15 | txt_f.write('%lf\n'% (float(row[7])) ) -------------------------------------------------------------------------------- /src/uav_simulator/local_sensing/src/cuda_exception.cuh: -------------------------------------------------------------------------------- 1 | // This file is part of REMODE - REgularized MOnocular Depth Estimation. 2 | // 3 | // Copyright (C) 2014 Matia Pizzoli 4 | // Robotics and Perception Group, University of Zurich, Switzerland 5 | // http://rpg.ifi.uzh.ch 6 | // 7 | // REMODE is free software: you can redistribute it and/or modify it under the 8 | // terms of the GNU General Public License as published by the Free Software 9 | // Foundation, either version 3 of the License, or any later version. 10 | // 11 | // REMODE is distributed in the hope that it will be useful, but WITHOUT ANY 12 | // WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS 13 | // FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. 14 | // 15 | // You should have received a copy of the GNU General Public License 16 | // along with this program. If not, see . 17 | 18 | #ifndef RMD_CUDA_EXCEPTION_CUH_ 19 | #define RMD_CUDA_EXCEPTION_CUH_ 20 | 21 | #include 22 | #include 23 | 24 | 25 | struct CudaException : public std::exception 26 | { 27 | CudaException(const std::string& what, cudaError err) 28 | : what_(what), err_(err) {} 29 | virtual ~CudaException() throw() {} 30 | virtual const char* what() const throw() 31 | { 32 | std::stringstream description; 33 | description << "CudaException: " << what_ << std::endl; 34 | if(err_ != cudaSuccess) 35 | { 36 | description << "cudaError code: " << cudaGetErrorString(err_); 37 | description << " (" << err_ << ")" << std::endl; 38 | } 39 | return description.str().c_str(); 40 | } 41 | std::string what_; 42 | cudaError err_; 43 | }; 44 | 45 | #endif /* RMD_CUDA_EXCEPTION_CUH_ */ 46 | -------------------------------------------------------------------------------- /src/uav_simulator/local_sensing/src/depth_render.cuh: -------------------------------------------------------------------------------- 1 | #ifndef DEPTH_RENDER_CUH 2 | #define DEPTH_RENDER_CUH 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | //#include 11 | 12 | #include "device_image.cuh" 13 | #include "cuda_exception.cuh" 14 | #include "helper_math.h" 15 | 16 | using namespace std; 17 | //using namespace Eigen; 18 | 19 | struct Parameter 20 | { 21 | int point_number; 22 | float fx, fy, cx, cy; 23 | int width, height; 24 | float r[3][3]; 25 | float t[3]; 26 | }; 27 | 28 | class DepthRender 29 | { 30 | public: 31 | DepthRender(); 32 | void set_para(float _fx, float _fy, float _cx, float _cy, int _width, int _height); 33 | ~DepthRender(); 34 | void set_data(vector &cloud_data); 35 | //void render_pose( Matrix3d &rotation, Vector3d &translation, int *host_ptr); 36 | //void render_pose( Matrix4d &transformation, int *host_ptr); 37 | void render_pose( double * transformation, int *host_ptr); 38 | 39 | private: 40 | int cloud_size; 41 | 42 | //data 43 | float3 *host_cloud_ptr; 44 | float3 *dev_cloud_ptr; 45 | bool has_devptr; 46 | 47 | //camera 48 | Parameter parameter; 49 | Parameter* parameter_devptr; 50 | }; 51 | 52 | #endif -------------------------------------------------------------------------------- /src/uav_simulator/local_sensing/src/empty.cpp: -------------------------------------------------------------------------------- 1 | #include "empty.h" -------------------------------------------------------------------------------- /src/uav_simulator/local_sensing/src/empty.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/local_sensing/src/empty.h -------------------------------------------------------------------------------- /src/uav_simulator/map_generator/.vscode/c_cpp_properties.json: -------------------------------------------------------------------------------- 1 | { 2 | "configurations": [ 3 | { 4 | "name": "Linux", 5 | "includePath": [ 6 | "${workspaceFolder}/**", 7 | "/usr/include/pcl-1.7", 8 | "/usr/include/eigen3", 9 | "/opt/ros/kinetic/include" 10 | ], 11 | "defines": [], 12 | "compilerPath": "/usr/bin/gcc", 13 | "cStandard": "c11", 14 | "cppStandard": "c++17" 15 | } 16 | ], 17 | "version": 4 18 | } -------------------------------------------------------------------------------- /src/uav_simulator/map_generator/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(map_generator) 3 | 4 | set(CMAKE_BUILD_TYPE "Release") 5 | #set(CMAKE_CXX_FLAGS "-std=c++11") 6 | ADD_COMPILE_OPTIONS(-std=c++11 ) 7 | ADD_COMPILE_OPTIONS(-std=c++14 ) 8 | set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g") 9 | 10 | find_package(catkin REQUIRED COMPONENTS 11 | roscpp 12 | rospy 13 | std_msgs 14 | geometry_msgs 15 | pcl_conversions 16 | ) 17 | find_package(PCL REQUIRED) 18 | find_package(Eigen3 REQUIRED) 19 | 20 | catkin_package() 21 | 22 | include_directories( 23 | # include 24 | ${catkin_INCLUDE_DIRS} 25 | ${EIGEN3_INCLUDE_DIR} 26 | ${PCL_INCLUDE_DIRS} 27 | ) 28 | 29 | add_executable (random_forest src/random_forest_sensing.cpp ) 30 | target_link_libraries(random_forest 31 | ${catkin_LIBRARIES} 32 | ${PCL_LIBRARIES}) 33 | -------------------------------------------------------------------------------- /src/uav_simulator/mockamap/include/maps.hpp: -------------------------------------------------------------------------------- 1 | #ifndef MAPS_HPP 2 | #define MAPS_HPP 3 | 4 | #include 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | namespace mocka { 11 | 12 | class Maps { 13 | public: 14 | typedef struct BasicInfo { 15 | ros::NodeHandle *nh_private; 16 | int sizeX; 17 | int sizeY; 18 | int sizeZ; 19 | int seed; 20 | double scale; 21 | sensor_msgs::PointCloud2 *output; 22 | pcl::PointCloud *cloud; 23 | } BasicInfo; 24 | 25 | BasicInfo getInfo() const; 26 | void setInfo(const BasicInfo &value); 27 | 28 | public: 29 | Maps(); 30 | 31 | public: 32 | void generate(int type); 33 | 34 | private: 35 | BasicInfo info; 36 | 37 | private: 38 | void pcl2ros(); 39 | 40 | void perlin3D(); 41 | void maze2D(); 42 | void randomMapGenerate(); 43 | void Maze3DGen(); 44 | void recursiveDivision(int xl, int xh, int yl, int yh, Eigen::MatrixXi &maze); 45 | void recursizeDivisionMaze(Eigen::MatrixXi &maze); 46 | void optimizeMap(); 47 | }; 48 | 49 | class MazePoint { 50 | private: 51 | pcl::PointXYZ point; 52 | double dist1; 53 | double dist2; 54 | int point1; 55 | int point2; 56 | bool isdoor; 57 | 58 | public: 59 | pcl::PointXYZ getPoint(); 60 | int getPoint1(); 61 | int getPoint2(); 62 | double getDist1(); 63 | double getDist2(); 64 | void setPoint(pcl::PointXYZ p); 65 | void setPoint1(int p); 66 | void setPoint2(int p); 67 | void setDist1(double set); 68 | void setDist2(double set); 69 | }; 70 | 71 | } // namespace mocka 72 | 73 | #endif // MAPS_HPP 74 | -------------------------------------------------------------------------------- /src/uav_simulator/mockamap/include/perlinnoise.hpp: -------------------------------------------------------------------------------- 1 | #ifndef PERLINNOISE_HPP 2 | #define PERLINNOISE_HPP 3 | 4 | #include 5 | 6 | // THIS CLASS IS A TRANSLATION TO C++11 FROM THE REFERENCE 7 | // JAVA IMPLEMENTATION OF THE IMPROVED PERLIN FUNCTION (see 8 | // http://mrl.nyu.edu/~perlin/noise/) 9 | // THE ORIGINAL JAVA IMPLEMENTATION IS COPYRIGHT 2002 KEN PERLIN 10 | 11 | // I ADDED AN EXTRA METHOD THAT GENERATES A NEW PERMUTATION VECTOR (THIS IS NOT 12 | // PRESENT IN THE ORIGINAL IMPLEMENTATION) 13 | 14 | class PerlinNoise 15 | { 16 | // The permutation vector 17 | std::vector p; 18 | 19 | public: 20 | // Initialize with the reference values for the permutation vector 21 | PerlinNoise(); 22 | // Generate a new permutation vector based on the value of seed 23 | PerlinNoise(unsigned int seed); 24 | // Get a noise value, for 2D images z can have any value 25 | double noise(double x, double y, double z); 26 | 27 | private: 28 | double fade(double t); 29 | double lerp(double t, double a, double b); 30 | double grad(int hash, double x, double y, double z); 31 | }; 32 | 33 | #endif // PERLINNOISE_HPP 34 | -------------------------------------------------------------------------------- /src/uav_simulator/mockamap/launch/maze2d.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 26 | 27 | -------------------------------------------------------------------------------- /src/uav_simulator/mockamap/launch/maze3d.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 26 | 27 | -------------------------------------------------------------------------------- /src/uav_simulator/mockamap/launch/perlin3d.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 19 | 21 | 22 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /src/uav_simulator/mockamap/launch/post2d.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 24 | 25 | -------------------------------------------------------------------------------- /src/uav_simulator/mockamap/src/.clang-format: -------------------------------------------------------------------------------- 1 | --- 2 | BasedOnStyle: Mozilla 3 | Standard: Cpp03 4 | AlignAfterOpenBracket: Align 5 | AlignConsecutiveAssignments: true 6 | AlignConsecutiveDeclarations: true 7 | AllowShortFunctionsOnASingleLine: false 8 | AllowShortIfStatementsOnASingleLine: false 9 | AllowShortLoopsOnASingleLine: false 10 | BreakBeforeBraces: Allman 11 | ... 12 | 13 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_control/config/corrections_hummingbird.yaml: -------------------------------------------------------------------------------- 1 | corrections: 2 | z: 0.0 3 | r: 0.0 4 | p: 0.0 5 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_control/config/corrections_pelican.yaml: -------------------------------------------------------------------------------- 1 | corrections: 2 | z: 0.0 3 | r: 0.0 4 | p: 0.0 5 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_control/config/gains.yaml: -------------------------------------------------------------------------------- 1 | # Gains for Laser-based Pelican 2 | gains: 3 | pos: {x: 5.0, y: 5.0, z: 15.0} 4 | vel: {x: 5.0, y: 5.0, z: 5.0} 5 | rot: {x: 3.5, y: 3.5, z: 1.0} 6 | ang: {x: 0.4, y: 0.4, z: 0.1} 7 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_control/config/gains_hummingbird.yaml: -------------------------------------------------------------------------------- 1 | # Vision Gain for Hummingbird 2 | gains: 3 | pos: {x: 2.0, y: 2.0, z: 3.5} 4 | vel: {x: 1.8, y: 1.8, z: 2.0} 5 | rot: {x: 1.0, y: 1.0, z: 0.3} 6 | ang: {x: 0.07, y: 0.07, z: 0.02} 7 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_control/config/gains_pelican.yaml: -------------------------------------------------------------------------------- 1 | # Gains for Laser-based Pelican 2 | gains: 3 | pos: {x: 5.0, y: 5.0, z: 15.0} 4 | vel: {x: 5.0, y: 5.0, z: 5.0} 5 | rot: {x: 3.5, y: 3.5, z: 1.0} 6 | ang: {x: 0.4, y: 0.4, z: 0.1} 7 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_control/include/so3_control/SO3Control.h: -------------------------------------------------------------------------------- 1 | #ifndef __SO3_CONTROL_H__ 2 | #define __SO3_CONTROL_H__ 3 | 4 | #include 5 | 6 | class SO3Control 7 | { 8 | public: 9 | SO3Control(); 10 | 11 | void setMass(const double mass); 12 | void setGravity(const double g); 13 | void setPosition(const Eigen::Vector3d& position); 14 | void setVelocity(const Eigen::Vector3d& velocity); 15 | void setAcc(const Eigen::Vector3d& acc); 16 | 17 | void calculateControl(const Eigen::Vector3d& des_pos, 18 | const Eigen::Vector3d& des_vel, 19 | const Eigen::Vector3d& des_acc, const double des_yaw, 20 | const double des_yaw_dot, const Eigen::Vector3d& kx, 21 | const Eigen::Vector3d& kv); 22 | 23 | const Eigen::Vector3d& getComputedForce(void); 24 | const Eigen::Quaterniond& getComputedOrientation(void); 25 | 26 | 27 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 28 | 29 | private: 30 | // Inputs for the controller 31 | double mass_; 32 | double g_; 33 | Eigen::Vector3d pos_; 34 | Eigen::Vector3d vel_; 35 | Eigen::Vector3d acc_; 36 | 37 | // Outputs of the controller 38 | Eigen::Vector3d force_; 39 | Eigen::Quaterniond orientation_; 40 | }; 41 | 42 | #endif 43 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_control/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b so3_control 6 | 7 | 10 | 11 | --> 12 | 13 | 14 | */ 15 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_control/nodelet_plugin.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | so3_control 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_control/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 0.0.0 3 | so3_control 4 | 5 | 6 | so3_control 7 | 8 | 9 | Kartik Mohta 10 | BSD 11 | http://ros.org/wiki/so3_control 12 | 13 | 14 | catkin 15 | 16 | roscpp 17 | nav_msgs 18 | quadrotor_msgs 19 | tf 20 | nodelet 21 | cmake_utils 22 | 23 | roscpp 24 | nav_msgs 25 | quadrotor_msgs 26 | tf 27 | nodelet 28 | cmake_utils 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(so3_quadrotor_simulator) 3 | 4 | add_compile_options(-std=c++11) 5 | 6 | set(CMAKE_BUILD_TYPE "Release") 7 | set(CMAKE_CXX_FLAGS "-std=c++11") 8 | set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g") 9 | 10 | find_package(catkin REQUIRED COMPONENTS 11 | roscpp 12 | quadrotor_msgs 13 | uav_utils 14 | cmake_utils 15 | ) 16 | 17 | ########### 18 | ## Build ## 19 | ########### 20 | 21 | find_package(Eigen3 REQUIRED) 22 | 23 | include_directories(${EIGEN3_INCLUDE_DIR}) 24 | include_directories(${CMAKE_CURRENT_SOURCE_DIR}/include/ode) 25 | ## 26 | find_package(Armadillo REQUIRED) 27 | include_directories(${ARMADILLO_INCLUDE_DIRS}) 28 | 29 | catkin_package( 30 | INCLUDE_DIRS include 31 | # LIBRARIES irobot_msgs 32 | CATKIN_DEPENDS roscpp quadrotor_msgs uav_utils 33 | DEPENDS Eigen3 system_lib 34 | ) 35 | 36 | include_directories(include) 37 | include_directories( 38 | ${catkin_INCLUDE_DIRS} 39 | ) 40 | 41 | add_library(quadrotor_dynamics src/dynamics/Quadrotor.cpp) 42 | 43 | ## Declare a cpp executable 44 | #add_executable(odom_visualization src/odom_visualization.cpp) 45 | add_executable(quadrotor_simulator_so3 46 | src/quadrotor_simulator_so3.cpp) 47 | 48 | target_link_libraries(quadrotor_simulator_so3 49 | ${catkin_LIBRARIES} 50 | quadrotor_dynamics 51 | ) 52 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/CHANGELOG: -------------------------------------------------------------------------------- 1 | odeint 2.1 2 | 3 | * versioning system 4 | * generation functions 5 | * bugfixing 6 | 7 | odeint 2.2 (still running) 8 | 9 | * removing same_size and resize from state_wrapper into separate functions 10 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/Jamroot: -------------------------------------------------------------------------------- 1 | # Copyright 2009 Karsten Ahnert and Mario Mulansky. 2 | # Distributed under the Boost Software License, Version 1.0. (See 3 | # accompanying file LICENSE_1_0.txt or copy at 4 | # http://www.boost.org/LICENSE_1_0.txt) 5 | 6 | import os ; 7 | import modules ; 8 | import path ; 9 | 10 | path-constant BOOST_ROOT : [ os.environ BOOST_ROOT ] ; 11 | 12 | project 13 | : requirements 14 | $(BOOST_ROOT) 15 | clang:-Wno-unused-variable 16 | ; 17 | 18 | # tests, regression tests and examples 19 | build-project libs/numeric/odeint/test ; 20 | build-project libs/numeric/odeint/examples ; 21 | 22 | 23 | # additional tests with external libraries : 24 | # build-project libs/numeric/odeint/test_external/gmp ; 25 | # build-project libs/numeric/odeint/test_external/mkl ; 26 | # build-project libs/numeric/odeint/test_external/gsl ; 27 | 28 | 29 | # docs: 30 | # build-project libs/numeric/odeint/doc ; 31 | 32 | 33 | 34 | 35 | 36 | 37 | ###### The following is copied from another sandbox project ##### 38 | ###### to get the quickbook and boostbook working ... ##### 39 | 40 | # local boost-root = [ modules.peek : BOOST_ROOT ] ; 41 | # local explore-header-include = $(top)/../.. ; 42 | # use-project /boost/regex : $(boost-root)/libs/regex/build ; 43 | 44 | ################################################################## 45 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/README: -------------------------------------------------------------------------------- 1 | odeint is a highly flexible library for solving ordinary differential equations. 2 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/algebra/detail/macros.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | boost/numeric/odeint/algebra/detail/macros.hpp 4 | 5 | [begin_description] 6 | Some macros for type checking. 7 | [end_description] 8 | 9 | Copyright 2009-2011 Karsten Ahnert 10 | Copyright 2009-2011 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | 18 | #ifndef BOOST_NUMERIC_ODEINT_ALGEBRA_DETAIL_MACROS_HPP_INCLUDED 19 | #define BOOST_NUMERIC_ODEINT_ALGEBRA_DETAIL_MACROS_HPP_INCLUDED 20 | 21 | 22 | //type traits aren't working with nvcc 23 | #ifndef __CUDACC__ 24 | #include 25 | #include 26 | 27 | #define BOOST_ODEINT_CHECK_CONTAINER_TYPE( Type1 , Type2 ) \ 28 | BOOST_STATIC_ASSERT(( boost::is_same< typename boost::remove_const< Type1 >::type , Type2 >::value )) 29 | 30 | #else 31 | //empty macro for nvcc 32 | #define BOOST_ODEINT_CHECK_CONTAINER_TYPE( Type1 , Type2 ) 33 | 34 | #endif // __CUDACC__ 35 | 36 | 37 | 38 | /* 39 | #define BOOST_ODEINT_CHECK_OPERATION_ARITY( Operation , Arity ) \ 40 | BOOST_STATIC_ASSERT(( boost::function_traits< Operation >::arity == Arity )) 41 | */ 42 | 43 | #endif // BOOST_NUMERIC_ODEINT_ALGEBRA_DETAIL_MACROS_HPP_INCLUDED 44 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/config.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | boost/numeric/odeint/config.hpp 4 | 5 | [begin_description] 6 | Sets configurations for odeint and used libraries. Should be included before any other odeint library 7 | [end_description] 8 | 9 | Copyright 2009-2011 Karsten Ahnert 10 | Copyright 2009-2011 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | #ifndef BOOST_NUMERIC_ODEINT_CONFIG_HPP_INCLUDED 18 | #define BOOST_NUMERIC_ODEINT_CONFIG_HPP_INCLUDED 19 | 20 | //increase macro variable to allow rk78 scheme 21 | #ifndef FUSION_MAX_VECTOR_SIZE 22 | #define FUSION_MAX_VECTOR_SIZE 15 23 | #endif 24 | 25 | /* 26 | * the following definitions are only required if fusion vectors are used as state types 27 | * in the rk78 scheme 28 | * they should be defined by the user if required, see e.g. libs/numeric/examples/harmonic_oscillator_units.cpp 29 | */ 30 | #ifndef BOOST_FUSION_INVOKE_MAX_ARITY 31 | #define BOOST_FUSION_INVOKE_MAX_ARITY 15 32 | #endif 33 | 34 | #ifndef BOOST_RESULT_OF_NUM_ARGS 35 | #define BOOST_RESULT_OF_NUM_ARGS 15 36 | #endif 37 | /* 38 | */ 39 | 40 | #include 41 | 42 | #if __cplusplus >= 201103L 43 | #define BOOST_NUMERIC_ODEINT_CXX11 1 44 | #endif 45 | 46 | 47 | #endif // BOOST_NUMERIC_ODEINT_CONFIG_HPP_INCLUDED 48 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/integrate/null_observer.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | boost/numeric/odeint/integrate/null_observer.hpp 4 | 5 | [begin_description] 6 | null_observer 7 | [end_description] 8 | 9 | Copyright 2009-2011 Karsten Ahnert 10 | Copyright 2009-2011 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | 18 | #ifndef BOOST_NUMERIC_ODEINT_INTEGRATE_NULL_OBSERVER_HPP_INCLUDED 19 | #define BOOST_NUMERIC_ODEINT_INTEGRATE_NULL_OBSERVER_HPP_INCLUDED 20 | 21 | namespace boost { 22 | namespace numeric { 23 | namespace odeint { 24 | 25 | struct null_observer 26 | { 27 | template< class State , class Time > 28 | void operator()( const State& /* x */ , Time /* t */ ) const 29 | { 30 | 31 | } 32 | }; 33 | 34 | } // namespace odeint 35 | } // namespace numeric 36 | } // namespace boost 37 | 38 | #endif // BOOST_NUMERIC_ODEINT_INTEGRATE_NULL_OBSERVER_HPP_INCLUDED 39 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/integrate/observer_collection.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | boost/numeric/odeint/integrate/observer_collection.hpp 4 | 5 | [begin_description] 6 | Collection of observers, which are all called during the evolution of the ODE. 7 | [end_description] 8 | 9 | Copyright 2009-2011 Karsten Ahnert 10 | Copyright 2009-2011 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | 18 | #ifndef BOOST_NUMERIC_ODEINT_INTEGRATE_OBSERVER_COLLECTION_HPP_INCLUDED 19 | #define BOOST_NUMERIC_ODEINT_INTEGRATE_OBSERVER_COLLECTION_HPP_INCLUDED 20 | 21 | #include 22 | 23 | #include 24 | 25 | namespace boost { 26 | namespace numeric { 27 | namespace odeint { 28 | 29 | template< class State , class Time > 30 | class observer_collection 31 | { 32 | public: 33 | 34 | typedef boost::function< void( const State& , const Time& ) > observer_type; 35 | typedef std::vector< observer_type > collection_type; 36 | 37 | void operator()( const State& x , Time t ) 38 | { 39 | for( size_t i=0 ; i 22 | #include 23 | 24 | #include 25 | #include 26 | 27 | #include 28 | #include 29 | #include 30 | #include 31 | 32 | 33 | #include 34 | 35 | 36 | #endif // BOOST_NUMERIC_ODEINT_STEPPER_GENERATION_HPP_INCLUDED 37 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/stepper/generation/generation_controlled_runge_kutta.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | boost/numeric/odeint/stepper/generation/generation_controlled_runge_kutta.hpp 4 | 5 | [begin_description] 6 | Specialization of the controller factory for the controlled_runge_kutta class. 7 | [end_description] 8 | 9 | Copyright 2009-2011 Karsten Ahnert 10 | Copyright 2009-2011 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | 18 | #ifndef BOOST_NUMERIC_ODEINT_STEPPER_GENERATION_GENERATION_CONTROLLED_RUNGE_KUTTA_HPP_INCLUDED 19 | #define BOOST_NUMERIC_ODEINT_STEPPER_GENERATION_GENERATION_CONTROLLED_RUNGE_KUTTA_HPP_INCLUDED 20 | 21 | #include 22 | #include 23 | 24 | 25 | namespace boost { 26 | namespace numeric { 27 | namespace odeint { 28 | 29 | 30 | // controller factory for controlled_runge_kutta 31 | template< class Stepper > 32 | struct controller_factory< Stepper , controlled_runge_kutta< Stepper > > 33 | { 34 | typedef Stepper stepper_type; 35 | typedef controlled_runge_kutta< stepper_type > controller_type; 36 | typedef typename controller_type::error_checker_type error_checker_type; 37 | typedef typename stepper_type::value_type value_type; 38 | 39 | controller_type operator()( value_type abs_error , value_type rel_error , const stepper_type &stepper ) 40 | { 41 | return controller_type( error_checker_type( abs_error , rel_error ) , stepper ); 42 | } 43 | }; 44 | 45 | 46 | 47 | 48 | } // odeint 49 | } // numeric 50 | } // boost 51 | 52 | 53 | #endif // BOOST_NUMERIC_ODEINT_STEPPER_GENERATION_GENERATION_CONTROLLED_RUNGE_KUTTA_HPP_INCLUDED 54 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/stepper/generation/generation_runge_kutta_cash_karp54.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | boost/numeric/odeint/stepper/generation/generation_runge_kutta_cash_karp54.hpp 4 | 5 | [begin_description] 6 | Enable the factory functions for the controller and the dense output of the Runge-Kutta-Cash-Karp 54 method. 7 | [end_description] 8 | 9 | Copyright 2009-2011 Karsten Ahnert 10 | Copyright 2009-2011 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | 18 | #ifndef BOOST_NUMERIC_ODEINT_STEPPER_GENERATION_GENERATION_RUNGE_KUTTA_CASH_KARP54_HPP_INCLUDED 19 | #define BOOST_NUMERIC_ODEINT_STEPPER_GENERATION_GENERATION_RUNGE_KUTTA_CASH_KARP54_HPP_INCLUDED 20 | 21 | #include 22 | #include 23 | #include 24 | 25 | 26 | namespace boost { 27 | namespace numeric { 28 | namespace odeint { 29 | 30 | // Specializations for runge_kutta_cash_karp54 31 | template< class State , class Value , class Deriv , class Time , class Algebra , class Operations , class Resize > 32 | struct get_controller< runge_kutta_cash_karp54< State , Value , Deriv , Time , Algebra , Operations , Resize > > 33 | { 34 | typedef runge_kutta_cash_karp54< State , Value , Deriv , Time , Algebra , Operations , Resize > stepper_type; 35 | typedef controlled_runge_kutta< stepper_type > type; 36 | }; 37 | 38 | 39 | 40 | 41 | 42 | } // odeint 43 | } // numeric 44 | } // boost 45 | 46 | 47 | #endif // BOOST_NUMERIC_ODEINT_STEPPER_GENERATION_GENERATION_RUNGE_KUTTA_CASH_KARP54_HPP_INCLUDED 48 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/stepper/generation/generation_runge_kutta_fehlberg78.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | boost/numeric/odeint/stepper/generation/generation_runge_kutta_fehlberg78.hpp 4 | 5 | [begin_description] 6 | Enable the factory functions for the controller and the dense output of the Runge-Kutta-Fehlberg 78 method. 7 | [end_description] 8 | 9 | Copyright 2009-2011 Karsten Ahnert 10 | Copyright 2009-2011 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | 18 | #ifndef BOOST_NUMERIC_ODEINT_STEPPER_GENERATION_GENERATION_RUNGE_KUTTA_FEHLBERG78_HPP_INCLUDED 19 | #define BOOST_NUMERIC_ODEINT_STEPPER_GENERATION_GENERATION_RUNGE_KUTTA_FEHLBERG78_HPP_INCLUDED 20 | 21 | #include 22 | #include 23 | #include 24 | 25 | namespace boost { 26 | namespace numeric { 27 | namespace odeint { 28 | 29 | 30 | template< class State , class Value , class Deriv , class Time , class Algebra , class Operations , class Resize > 31 | struct get_controller< runge_kutta_fehlberg78< State , Value , Deriv , Time , Algebra , Operations , Resize > > 32 | { 33 | typedef runge_kutta_fehlberg78< State , Value , Deriv , Time , Algebra , Operations , Resize > stepper_type; 34 | typedef controlled_runge_kutta< stepper_type > type; 35 | }; 36 | 37 | 38 | 39 | 40 | 41 | } // odeint 42 | } // numeric 43 | } // boost 44 | 45 | 46 | #endif // BOOST_NUMERIC_ODEINT_STEPPER_GENERATION_GENERATION_RUNGE_KUTTA_FEHLBERG78_HPP_INCLUDED 47 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/util/bind.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * [begin_description] 3 | * Boost bind pull the placeholders, _1, _2, ... into global 4 | * namespace. This can conflict with the C++03 TR1 and C++11 5 | * std::placeholders. This header provides a workaround for 6 | * this problem. 7 | * [end_description] 8 | * 9 | * Copyright 2012 Christoph Koke 10 | * 11 | * Distributed under the Boost Software License, Version 1.0. 12 | * (See accompanying file LICENSE_1_0.txt or 13 | * copy at http://www.boost.org/LICENSE_1_0.txt) 14 | * */ 15 | 16 | #ifndef BOOST_NUMERIC_ODEINT_UTIL_BIND_HPP_INCLUDED 17 | #define BOOST_NUMERIC_ODEINT_UTIL_BIND_HPP_INCLUDED 18 | 19 | 20 | #include 21 | 22 | 23 | #if BOOST_NUMERIC_ODEINT_CXX11 24 | #include 25 | #else 26 | #include 27 | #endif 28 | 29 | namespace boost { 30 | namespace numeric { 31 | namespace odeint { 32 | namespace detail { 33 | 34 | #if BOOST_NUMERIC_ODEINT_CXX11 35 | 36 | using ::std::bind; 37 | using namespace ::std::placeholders; 38 | 39 | 40 | #else 41 | 42 | using ::boost::bind; 43 | using ::_1; 44 | using ::_2; 45 | 46 | #endif 47 | 48 | } 49 | } 50 | } 51 | } 52 | 53 | #endif // BOOST_NUMERIC_ODEINT_UTIL_BIND_HPP_INCLUDED 54 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/util/detail/less_with_sign.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | boost/numeric/odeint/integrate/detail/less_with_sign.hpp 4 | 5 | [begin_description] 6 | Helper function to compare times taking into account the sign of dt 7 | [end_description] 8 | 9 | Copyright 2009-2012 Karsten Ahnert 10 | Copyright 2009-2012 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | #ifndef BOOST_NUMERIC_ODEINT_INTEGRATE_DETAIL_LESS_WITH_SIGN_HPP_INCLUDED 18 | #define BOOST_NUMERIC_ODEINT_INTEGRATE_DETAIL_LESS_WITH_SIGN_HPP_INCLUDED 19 | 20 | #include 21 | 22 | namespace boost { 23 | namespace numeric { 24 | namespace odeint { 25 | namespace detail { 26 | 27 | /** 28 | * return t1 < t2 if dt > 0 and t1 > t2 if dt < 0 29 | */ 30 | template< typename T1 , typename T2 , typename T3 > 31 | bool less_with_sign( T1 t1 , T2 t2 , T3 dt ) 32 | { 33 | if( get_unit_value(dt) > 0 ) 34 | return t1 < t2; 35 | else 36 | return t1 > t2; 37 | } 38 | 39 | /** 40 | * return t1 <= t2 if dt > 0 and t1 => t2 if dt < 0 41 | */ 42 | template< typename T1 , typename T2 , typename T3> 43 | bool less_eq_with_sign( T1 t1 , T2 t2 , T3 dt ) 44 | { 45 | if( get_unit_value(dt) > 0 ) 46 | return t1 <= t2; 47 | else 48 | return t1 >= t2; 49 | } 50 | 51 | } } } } 52 | 53 | #endif 54 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/util/is_pair.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | boost/numeric/odeint/util/is_pair.hpp 4 | 5 | [begin_description] 6 | Metafunction to determine if a type is a std::pair<>. 7 | [end_description] 8 | 9 | Copyright 2009-2011 Karsten Ahnert 10 | Copyright 2009-2011 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | 18 | #ifndef BOOST_NUMERIC_ODEINT_UTIL_IS_PAIR_HPP_INCLUDED 19 | #define BOOST_NUMERIC_ODEINT_UTIL_IS_PAIR_HPP_INCLUDED 20 | 21 | 22 | #include 23 | #include 24 | 25 | 26 | namespace boost { 27 | namespace numeric { 28 | namespace odeint { 29 | 30 | template< class T > 31 | struct is_pair : public boost::mpl::false_ 32 | { 33 | }; 34 | 35 | template< class T1 , class T2 > 36 | struct is_pair< std::pair< T1 , T2 > > : public boost::mpl::true_ 37 | { 38 | }; 39 | 40 | } // namespace odeint 41 | } // namespace numeric 42 | } // namespace boost 43 | 44 | 45 | #endif // BOOST_NUMERIC_ODEINT_UTIL_IS_PAIR_HPP_INCLUDED 46 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/util/same_instance.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | boost/numeric/odeint/util/same_instance.hpp 4 | 5 | [begin_description] 6 | Basic check if two variables are the same instance 7 | [end_description] 8 | 9 | Copyright 2009-2012 Karsten Ahnert 10 | Copyright 2009-2012 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | 18 | #ifndef BOOST_NUMERIC_ODEINT_UTIL_SAME_INSTANCE_HPP_INCLUDED 19 | #define BOOST_NUMERIC_ODEINT_UTIL_SAME_INSTANCE_HPP_INCLUDED 20 | 21 | namespace boost { 22 | namespace numeric { 23 | namespace odeint { 24 | 25 | template< class T1 , class T2 , class Enabler=void > 26 | struct same_instance_impl 27 | { 28 | static bool same_instance( const T1 &x1 , const T2 &x2 ) 29 | { 30 | return false; 31 | } 32 | }; 33 | 34 | template< class T > 35 | struct same_instance_impl< T , T > 36 | { 37 | static bool same_instance( const T &x1 , const T &x2 ) 38 | { 39 | // check pointers 40 | return (&x1 == &x2); 41 | } 42 | }; 43 | 44 | 45 | template< class T1 , class T2 > 46 | bool same_instance( const T1 &x1 , const T2 &x2 ) 47 | { 48 | return same_instance_impl< T1 , T2 >::same_instance( x1 , x2 ); 49 | } 50 | 51 | 52 | } // namespace odeint 53 | } // namespace numeric 54 | } // namespace boost 55 | 56 | #endif 57 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/util/state_wrapper.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | boost/numeric/odeint/util/state_wrapper.hpp 4 | 5 | [begin_description] 6 | State wrapper for the state type in all stepper. The state wrappers are responsible for construction, 7 | destruction, copying construction, assignment and resizing. 8 | [end_description] 9 | 10 | Copyright 2009-2011 Karsten Ahnert 11 | Copyright 2009-2011 Mario Mulansky 12 | 13 | Distributed under the Boost Software License, Version 1.0. 14 | (See accompanying file LICENSE_1_0.txt or 15 | copy at http://www.boost.org/LICENSE_1_0.txt) 16 | */ 17 | 18 | 19 | #ifndef BOOST_NUMERIC_ODEINT_UTIL_STATE_WRAPPER_HPP_INCLUDED 20 | #define BOOST_NUMERIC_ODEINT_UTIL_STATE_WRAPPER_HPP_INCLUDED 21 | 22 | 23 | #include 24 | 25 | #include 26 | #include 27 | #include 28 | 29 | 30 | namespace boost { 31 | namespace numeric { 32 | namespace odeint { 33 | 34 | 35 | template< class V , class Enabler = void > 36 | struct state_wrapper 37 | { 38 | typedef state_wrapper< V > state_wrapper_type; 39 | 40 | V m_v; 41 | }; 42 | 43 | 44 | } 45 | } 46 | } 47 | 48 | 49 | 50 | #endif // BOOST_NUMERIC_ODEINT_UTIL_STATE_WRAPPER_HPP_INCLUDED 51 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/boost/numeric/odeint/version.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | boost/numeric/odeint/version.hpp 4 | 5 | [begin_description] 6 | Defines the current version of odeint. 7 | [end_description] 8 | 9 | Copyright 2009-2012 Karsten Ahnert 10 | Copyright 2009-2012 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | #ifndef BOOST_NUMERIC_ODEINT_VERSION_HPP_INCLUDED 18 | #define BOOST_NUMERIC_ODEINT_VERSION_HPP_INCLUDED 19 | 20 | #include 21 | #include 22 | 23 | 24 | #define ODEINT_MAJOR_VERSION 2 25 | #define ODEINT_MINOR_VERSION 2 26 | #define ODEINT_PATCH_LEVEL 0 27 | #define ODEINT_VERSION ( ODEINT_MAJOR_VERSION * 100000 + ODEINT_MINOR_VERSION * 100 + ODEINT_PATCH_LEVEL ) 28 | 29 | 30 | namespace boost { 31 | namespace numeric { 32 | namespace odeint { 33 | 34 | namespace version { 35 | 36 | const int major = ODEINT_MAJOR_VERSION ; 37 | const int minor = ODEINT_MINOR_VERSION ; 38 | const int patch_level = ODEINT_PATCH_LEVEL ; 39 | 40 | } 41 | 42 | inline std::string get_version_string( void ) 43 | { 44 | std::ostringstream str; 45 | str << "v" << version::major << "." << version::minor; 46 | if( version::patch_level != 0 ) str << "_" << version::patch_level; 47 | return str.str(); 48 | } 49 | 50 | 51 | } 52 | } 53 | } 54 | 55 | #endif // BOOST_NUMERIC_ODEINT_VERSION_HPP_INCLUDED 56 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/acknowledgements.qbk: -------------------------------------------------------------------------------- 1 | [/============================================================================ 2 | Boost.odeint 3 | 4 | Copyright (c) 2009-2012 Karsten Ahnert 5 | Copyright (c) 2009-2012 Mario Mulansky 6 | 7 | Use, modification and distribution is subject to the Boost Software License, 8 | Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at 9 | http://www.boost.org/LICENSE_1_0.txt) 10 | =============================================================================/] 11 | 12 | 13 | [section Acknowledgments] 14 | 15 | 16 | [/ 17 | 18 | * Steven Watanabe for managing the Boost review process. 19 | * All people who participated in the odeint review process on the Boost mailing list. 20 | * Paul Bristow for helping with the documentation. 21 | * The Google Summer Of Code (GSOC) program for funding and Andrew Sutton for supervising us during the GSOC and for lots of useful discussions and feedback about many implementation details.. 22 | * Joachim Faulhaber for motivating us to participate in the Boost review process and many detailed comments about the library. 23 | * All users of odeint. They are the main motivation for our efforts. 24 | 25 | 26 | [h3 Contributers] 27 | 28 | * Andreas Angelopoulos implemented the sparse matrix implicit Euler stepper using the MTL4 library. 29 | * Rajeev Singh implemented the stiff Van der Pol oscillator example. 30 | * Sylwester Arabas improved the documentation. 31 | * Denis Demidov provided the adaption to the VexCL and Viennacl libraries. 32 | * Christoph Koke provided improved binders. 33 | * Lee Hodgkinson provided the black hole example. 34 | ] 35 | 36 | 37 | [endsect] 38 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/concepts.qbk: -------------------------------------------------------------------------------- 1 | [/============================================================================ 2 | Boost.odeint 3 | 4 | Copyright (c) 2009-2012 Karsten Ahnert 5 | Copyright (c) 2009-2012 Mario Mulansky 6 | 7 | Use, modification and distribution is subject to the Boost Software License, 8 | Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at 9 | http://www.boost.org/LICENSE_1_0.txt) 10 | =============================================================================/] 11 | 12 | 13 | [section:concepts Concepts] 14 | [# odeint.concepts] 15 | 16 | [include concepts/system.qbk] 17 | [include concepts/symplectic_system.qbk] 18 | [include concepts/implicit_system.qbk] 19 | [include concepts/stepper.qbk] 20 | [include concepts/error_stepper.qbk] 21 | [include concepts/controlled_stepper.qbk] 22 | [include concepts/dense_output_stepper.qbk] 23 | [include concepts/state_algebra_operations.qbk] 24 | [include concepts/state_wrapper.qbk] 25 | 26 | [endsect] -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/concepts/state_wrapper.qbk: -------------------------------------------------------------------------------- 1 | [/============================================================================ 2 | Boost.odeint 3 | 4 | Copyright (c) 2009-2012 Karsten Ahnert 5 | Copyright (c) 2009-2012 Mario Mulansky 6 | 7 | Use, modification and distribution is subject to the Boost Software License, 8 | Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at 9 | http://www.boost.org/LICENSE_1_0.txt) 10 | =============================================================================/] 11 | 12 | 13 | [section State Wrapper] 14 | 15 | [heading Description] 16 | 17 | The `State Wrapper` concept describes the way odeint creates temporary state objects to store intermediate results within the stepper's `do_step` methods. 18 | 19 | [heading Notation] 20 | 21 | [variablelist 22 | [[`State`] [A type that is the `state_type` of the ODE]] 23 | [[`WrappedState`] [A type that is a model of State Wrapper for the state type `State`.]] 24 | [[`x`] [Object of type `State`]] 25 | [[`w`] [Object of type `WrappedState`]] 26 | ] 27 | 28 | [heading Valid Expressions] 29 | 30 | [table 31 | [[Name] [Expression] [Type] [Semantics]] 32 | [[Get resizeability] [`is_resizeable< State >`] [`boost::false_type` or `boost::true_type`] [Returns `boost::true_type` if the `State` is resizeable, `boost::false_type` otherwise.]] 33 | [[Create `WrappedState` type] [`state_wrapper< State >`] [`WrappedState`] [Creates the type for a `WrappedState` for the state type `State`]] 34 | [[Constructor] [`WrappedState()`] [`WrappedState`] [Constructs a state wrapper with an empty state]] 35 | [[Copy Constructor] [`WrappedState( w )`] [`WrappedState`] [Constructs a state wrapper with a state of the same size as the state in `w`]] 36 | [[Get state] [`w.m_v`] [`State`] [Returns the `State` object of this state wrapper.]] 37 | ] 38 | 39 | [endsect] -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/concepts/system.qbk: -------------------------------------------------------------------------------- 1 | [/============================================================================ 2 | Boost.odeint 3 | 4 | Copyright (c) 2009-2012 Karsten Ahnert 5 | Copyright (c) 2009-2012 Mario Mulansky 6 | 7 | Use, modification and distribution is subject to the Boost Software License, 8 | Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at 9 | http://www.boost.org/LICENSE_1_0.txt) 10 | =============================================================================/] 11 | 12 | 13 | [section System] 14 | 15 | [heading Description] 16 | 17 | The System concept models the algorithmic implementation of the rhs. of the ODE ['x' = f(x,t)]. 18 | The only requirement for this concept is that it should be callable with a specific parameter syntax (see below). 19 | A System is typically implemented as a function or a functor. 20 | Systems fulfilling this concept are required by all Runge-Kutta steppers as well as the Bulirsch-Stoer steppers. 21 | However, symplectic and implicit steppers work with other system concepts, see __symplectic_system and __implicit_system. 22 | 23 | [heading Notation] 24 | 25 | [variablelist 26 | [[`System`] [A type that is a model of System]] 27 | [[`State`] [A type representing the state /x/ of the ODE]] 28 | [[`Deriv`] [A type representing the derivative /x'/ of the ODE]] 29 | [[`Time`] [A type representing the time]] 30 | [[`sys`] [An object of type `System`]] 31 | [[`x`] [Object of type `State`]] 32 | [[`dxdt`] [Object of type `Deriv`]] 33 | [[`t`] [Object of type `Time`]] 34 | ] 35 | 36 | [heading Valid expressions] 37 | 38 | [table 39 | [[Name] [Expression] [Type] [Semantics]] 40 | [[Calculate ['dx/dt := f(x,t)]] [`sys( x , dxdt , t )`] [`void`] [Calculates f(x,t), the result is stored into dxdt] ] 41 | ] 42 | 43 | [endsect] -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/details.qbk: -------------------------------------------------------------------------------- 1 | [/============================================================================ 2 | Boost.odeint 3 | 4 | Copyright (c) 2009-2012 Karsten Ahnert 5 | Copyright (c) 2009-2012 Mario Mulansky 6 | 7 | Use, modification and distribution is subject to the Boost Software License, 8 | Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at 9 | http://www.boost.org/LICENSE_1_0.txt) 10 | =============================================================================/] 11 | 12 | [section odeint in detail] 13 | 14 | [include details_steppers.qbk] 15 | 16 | [include details_generation_functions.qbk] 17 | 18 | [include details_integrate_functions.qbk] 19 | 20 | [include details_state_types_algebras_operations.qbk] 21 | 22 | [include details_boost_ref.qbk] 23 | 24 | [include details_boost_range.qbk] 25 | 26 | [include details_bind_member_functions.qbk] 27 | 28 | [endsect] 29 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/details_bind_member_functions.qbk: -------------------------------------------------------------------------------- 1 | [/============================================================================ 2 | Boost.odeint 3 | 4 | Copyright (c) 2009-2012 Karsten Ahnert 5 | Copyright (c) 2009-2012 Mario Mulansky 6 | 7 | Use, modification and distribution is subject to the Boost Software License, 8 | Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at 9 | http://www.boost.org/LICENSE_1_0.txt) 10 | =============================================================================/] 11 | 12 | 13 | [section Binding member functions] 14 | 15 | [import ../examples/bind_member_functions.cpp] 16 | 17 | Binding member functions to a function objects suitable for odeint system function is not easy, at least in C++03. The usual way of using __boost_bind does not work because of the forwarding problem. odeint provides two `do_step` method which only differ in the const specifiers of the arguments and __boost_bind binders only provide the specializations up to two argument which is not enough for odeint. 18 | 19 | But one can easily implement the according binders themself: 20 | 21 | [ode_wrapper] 22 | 23 | One can use this binder as follows 24 | 25 | [bind_member_function] 26 | 27 | [section Binding member functions in C++11] 28 | 29 | [import ../examples/bind_member_functions_cpp11.cpp] 30 | In C++11 one can use `std::bind` and one does not need to implement the bind themself: 31 | 32 | [bind_member_function_cpp11] 33 | 34 | [endsect] 35 | 36 | [endsect] 37 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/details_boost_ref.qbk: -------------------------------------------------------------------------------- 1 | [/============================================================================ 2 | Boost.odeint 3 | 4 | Copyright (c) 2009-2012 Karsten Ahnert 5 | Copyright (c) 2009-2012 Mario Mulansky 6 | 7 | Use, modification and distribution is subject to the Boost Software License, 8 | Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at 9 | http://www.boost.org/LICENSE_1_0.txt) 10 | =============================================================================/] 11 | 12 | [section Using boost::ref] 13 | 14 | In odeint all system functions and observers are passed by value. For example, if you call a `do_step` method of a particular stepper or the integration functions, your system and your stepper will be passed by value: 15 | 16 | [c++] 17 | `` 18 | rk4.do_step( sys , x , t , dt ); // pass sys by value 19 | `` 20 | 21 | This behavior is suitable for most systems, especially if your system does not contain any data or only a few parameters. However, in some cases you might contain some large amount of data with you system function and passing them by value is not desired since the data would be copied. 22 | 23 | In such cases you can easily use `boost::ref` (and its relative `boost::cref`) 24 | which passes its argument by reference (or constant reference). odeint will 25 | unpack the arguments and no copying at all of your system object will take place: 26 | 27 | `` 28 | rk4.do_step( boost::ref( sys ) , x , t , dt ); // pass sys as references 29 | `` 30 | 31 | The same mechanism can be used for the observers in the integrate functions. 32 | 33 | [tip If you are using C++11 you can also use `std::ref` and `std::cref`] 34 | 35 | [endsect] 36 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/alert.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/alert.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/blank.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/blank.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/1.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/1.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/10.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/10.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/10.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 13 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/11.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/11.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/11.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/12.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/12.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/12.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 13 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/13.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/13.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/13.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 13 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/14.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/14.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/14.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 13 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/15.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/15.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/15.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 13 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/16.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 13 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/17.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 13 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/18.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 13 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/19.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 13 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/2.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/2.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/20.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 15 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/21.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/22.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 15 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/23.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 15 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/24.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 15 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/25.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 15 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/26.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 15 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/27.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 15 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/28.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 15 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/29.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 15 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/3.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/3.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/30.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 17 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/4.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/4.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/4.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/5.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/5.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/5.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/6.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/6.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/6.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/7.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/7.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/8.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/8.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/8.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/9.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/9.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/callouts/9.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | ]> 7 | 9 | 10 | 11 | 12 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/caution.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/caution.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/draft.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/draft.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/home.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/home.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/important.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/important.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/important.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | ]> 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/next.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/next.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/next.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | ]> 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/next_disabled.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/next_disabled.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/note.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/note.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/prev.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/prev.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/prev.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | ]> 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/prev_disabled.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/prev_disabled.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/smiley.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/smiley.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/tip.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/tip.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/toc-blank.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/toc-blank.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/toc-minus.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/toc-minus.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/toc-plus.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/toc-plus.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/up.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/up.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/up.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | ]> 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/up_disabled.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/up_disabled.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/warning.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/warning.png -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/images/warning.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | ]> 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/logo.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/logo.jpg -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/phase_lattice_2d_0000.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/phase_lattice_2d_0000.jpg -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/phase_lattice_2d_0100.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/phase_lattice_2d_0100.jpg -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/phase_lattice_2d_1000.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/phase_lattice_2d_1000.jpg -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/solar_system.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/ego-planner/bfda51284c8c1b476043255a8145ef925a3778a5/src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/html/solar_system.jpg -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/make_controlled_table.qbk: -------------------------------------------------------------------------------- 1 | [/============================================================================ 2 | Boost.odeint 3 | 4 | Copyright (c) 2009-2012 Karsten Ahnert 5 | Copyright (c) 2009-2012 Mario Mulansky 6 | 7 | Use, modification and distribution is subject to the Boost Software License, 8 | Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at 9 | http://www.boost.org/LICENSE_1_0.txt) 10 | =============================================================================/] 11 | 12 | 13 | 14 | [table Generation functions make_controlled( abs_error , rel_error , stepper ) 15 | [[Stepper] [Result of make_controlled] [Remarks]] 16 | [[`runge_kutta_cash_karp54`] [`controlled_runge_kutta< runge_kutta_cash_karp54 , default_error_checker<...> >`] [['a[sub x]=1], ['a[sub dxdt]=1]]] 17 | [[`runge_kutta_fehlberg78`] [`controlled_runge_kutta< runge_kutta_fehlberg78 , default_error_checker<...> >`] [['a[sub x]=1], ['a[sub dxdt]=1]]] 18 | [[`runge_kutta_dopri5`] [`controlled_runge_kutta< runge_kutta_dopri5 , default_error_checker<...> >`] [['a [sub x]=1], ['a[sub dxdt]=1]]] 19 | [[`rosenbrock4`] [`rosenbrock4_controlled< rosenbrock4 >`] [-]] 20 | ] 21 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/make_dense_output_table.qbk: -------------------------------------------------------------------------------- 1 | [/============================================================================ 2 | Boost.odeint 3 | 4 | Copyright (c) 2009-2012 Karsten Ahnert 5 | Copyright (c) 2009-2012 Mario Mulansky 6 | 7 | Use, modification and distribution is subject to the Boost Software License, 8 | Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at 9 | http://www.boost.org/LICENSE_1_0.txt) 10 | =============================================================================/] 11 | 12 | 13 | 14 | [table Generation functions make_dense_output( abs_error , rel_error , stepper ) 15 | [[Stepper] [Result of make_dense_output] [Remarks]] 16 | [[`runge_kutta_dopri5`] [`dense_output_runge_kutta< controlled_runge_kutta< runge_kutta_dopri5 , default_error_checker<...> > >`] [['a [sub x]=1], ['a[sub dxdt]=1]]] 17 | [[`rosenbrock4`] [`rosenbrock4_dense_output< rosenbrock4_controller< rosenbrock4 > >`] [-]] 18 | ] 19 | 20 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/odeint.idx: -------------------------------------------------------------------------------- 1 | # odeint.idx list of files and keyword to be indexed. 2 | 3 | # Copyright (c) 2011 Pierre Talbot 4 | # 5 | # Use, modification and distribution is subject to the Boost Software 6 | # License, Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at 7 | # http://www.boost.org/LICENSE_1_0.txt) 8 | 9 | !scan-path "boost/numeric/odeint/" ".*\.*pp" true 10 | # recurse in any sub-directories. 11 | 12 | # List of terms in the docbook (from Quickbook) to be indexed. 13 | # Convenient to order these alphabetically. 14 | 15 | # TODO - add more! 16 | 17 | acknowledgements 18 | book 19 | # C++ \ 20 | card 21 | credit 22 | deprecated 23 | Doxygen 24 | example \ 25 | equations \ 26 | graphics \ 27 | Gumm 28 | links \ 29 | images \ 30 | ISBN 31 | ISSN 32 | IBM 33 | italic \ 34 | # index index and indexes (assume not using plural indices!) 35 | index \ 36 | Luhn 37 | Mastercard 38 | modulus 39 | path \ 40 | pre-conditions \ 41 | post-conditions \ 42 | remark \ 43 | snippet \ 44 | png 45 | Quickbook 46 | Verhoeff 47 | # version \ 48 | VISA 49 | warning \ 50 | 51 | # Remove leading "A" or "The" prefixes from section titles. 52 | # !rewrite-name "(?:A|An|The)\s+(.*)" "\1" 53 | 54 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/doc/tutorial.qbk: -------------------------------------------------------------------------------- 1 | [/============================================================================ 2 | Boost.odeint 3 | 4 | Copyright (c) 2009-2012 Karsten Ahnert 5 | Copyright (c) 2009-2012 Mario Mulansky 6 | 7 | Use, modification and distribution is subject to the Boost Software License, 8 | Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at 9 | http://www.boost.org/LICENSE_1_0.txt) 10 | =============================================================================/] 11 | 12 | 13 | [section Tutorial] 14 | 15 | 16 | [include tutorial_harmonic_oscillator.qbk] 17 | 18 | [include tutorial_solar_system.qbk] 19 | 20 | [include tutorial_chaotic_system.qbk] 21 | 22 | [include tutorial_stiff_systems.qbk] 23 | 24 | [include tutorial_special_topics.qbk] 25 | 26 | [include tutorial_thrust_cuda.qbk] 27 | 28 | [include tutorial_vexcl_opencl.qbk] 29 | 30 | 31 | [section All examples] 32 | 33 | The following table gives an overview over all examples. 34 | 35 | [include examples_table.qbk] 36 | 37 | [endsect] 38 | 39 | 40 | 41 | 42 | 43 | 44 | [endsect] 45 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/examples/2d_lattice/Jamfile.v2: -------------------------------------------------------------------------------- 1 | # Copyright 2011 Karsten Ahnert and Mario Mulansky. 2 | # Distributed under the Boost Software License, Version 1.0. (See 3 | # accompanying file LICENSE_1_0.txt or copy at 4 | # http://www.boost.org/LICENSE_1_0.txt) 5 | 6 | project 7 | : requirements 8 | ../../../../.. 9 | BOOST_ALL_NO_LIB=1 10 | ; 11 | 12 | exe spreading : spreading.cpp ; -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/examples/2d_lattice/nested_range_algebra.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright 2009-2012 Karsten Ahnert 3 | Copyright 2009-2012 Mario Mulansky 4 | 5 | Distributed under the Boost Software License, Version 1.0. 6 | (See accompanying file LICENSE_1_0.txt or 7 | copy at http://www.boost.org/LICENSE_1_0.txt) 8 | */ 9 | 10 | 11 | /* nested range algebra */ 12 | 13 | #ifndef NESTED_RANGE_ALGEBRA 14 | #define NESTED_RANGE_ALGEBRA 15 | 16 | namespace detail { 17 | 18 | template< class Iterator1 , class Iterator2 , class Iterator3 , class Operation , class Algebra > 19 | void for_each3( Iterator1 first1 , Iterator1 last1 , Iterator2 first2 , Iterator3 first3, Operation op , Algebra &algebra ) 20 | { 21 | for( ; first1 != last1 ; ) 22 | algebra.for_each3( *first1++ , *first2++ , *first3++ , op ); 23 | } 24 | } 25 | 26 | 27 | template< class InnerAlgebra > 28 | struct nested_range_algebra 29 | { 30 | 31 | nested_range_algebra() 32 | : m_inner_algebra() 33 | { } 34 | 35 | template< class S1 , class S2 , class S3 , class Op > 36 | void for_each3( S1 &s1 , S2 &s2 , S3 &s3 , Op op ) 37 | { 38 | detail::for_each3( boost::begin( s1 ) , boost::end( s1 ) , boost::begin( s2 ) , boost::begin( s3 ) , op , m_inner_algebra ); 39 | } 40 | 41 | 42 | private: 43 | InnerAlgebra m_inner_algebra; 44 | }; 45 | 46 | #endif 47 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/examples/Jamfile.v2: -------------------------------------------------------------------------------- 1 | # Copyright 2009 Karsten Ahnert and Mario Mulansky. 2 | # Distributed under the Boost Software License, Version 1.0. (See 3 | # accompanying file LICENSE_1_0.txt or copy at 4 | # http://www.boost.org/LICENSE_1_0.txt) 5 | 6 | 7 | project 8 | : requirements 9 | ../../../.. 10 | BOOST_ALL_NO_LIB=1 11 | : 12 | ; 13 | 14 | 15 | exe harmonic_oscillator : harmonic_oscillator.cpp ; 16 | exe solar_system : solar_system.cpp ; 17 | exe chaotic_system : chaotic_system.cpp ; 18 | exe stiff_system : stiff_system.cpp ; 19 | exe fpu : fpu.cpp ; 20 | exe phase_oscillator_ensemble : phase_oscillator_ensemble.cpp ; 21 | exe harmonic_oscillator_units : harmonic_oscillator_units.cpp ; 22 | exe stuart_landau : stuart_landau.cpp ; 23 | exe two_dimensional_phase_lattice : two_dimensional_phase_lattice.cpp ; 24 | exe bulirsch_stoer : bulirsch_stoer.cpp ; 25 | exe elliptic_functions : elliptic_functions.cpp ; 26 | exe resizing_lattice : resizing_lattice.cpp ; 27 | exe list_lattice : list_lattice.cpp ; 28 | exe stepper_details : stepper_details.cpp ; 29 | exe my_vector : my_vector.cpp ; 30 | exe lorenz_point : lorenz_point.cpp ; 31 | exe van_der_pol_stiff : van_der_pol_stiff.cpp ; 32 | exe simple1d : simple1d.cpp ; 33 | exe stochastic_euler : stochastic_euler.cpp ; 34 | exe generation_functions : generation_functions.cpp ; 35 | exe heun : heun.cpp ; 36 | exe bind_member_functions : bind_member_functions.cpp ; 37 | exe bind_member_functions_cpp11 : bind_member_functions_cpp11.cpp : -std=c++0x ; 38 | 39 | # build-project mtl ; 40 | # build-project ublas ; 41 | # build-project gmpxx ; 42 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/examples/bind_member_functions_cpp11.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | libs/numeric/odeint/examples/bind_member_functions.hpp 4 | 5 | [begin_description] 6 | tba. 7 | [end_description] 8 | 9 | Copyright 2009-2012 Karsten Ahnert 10 | Copyright 2009-2012 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | #include 18 | #include 19 | #include 20 | 21 | #include 22 | 23 | namespace odeint = boost::numeric::odeint; 24 | 25 | 26 | 27 | typedef std::array< double , 3 > state_type; 28 | 29 | struct lorenz 30 | { 31 | void ode( const state_type &x , state_type &dxdt , double t ) const 32 | { 33 | const double sigma = 10.0; 34 | const double R = 28.0; 35 | const double b = 8.0 / 3.0; 36 | 37 | dxdt[0] = sigma * ( x[1] - x[0] ); 38 | dxdt[1] = R * x[0] - x[1] - x[0] * x[2]; 39 | dxdt[2] = -b * x[2] + x[0] * x[1]; 40 | } 41 | }; 42 | 43 | int main( int argc , char *argv[] ) 44 | { 45 | using namespace boost::numeric::odeint; 46 | //[ bind_member_function_cpp11 47 | namespace pl = std::placeholders; 48 | 49 | state_type x = {{ 10.0 , 10.0 , 10.0 }}; 50 | integrate_const( runge_kutta4< state_type >() , 51 | std::bind( &lorenz::ode , lorenz() , pl::_1 , pl::_2 , pl::_3 ) , 52 | x , 0.0 , 10.0 , 0.01 ); 53 | //] 54 | return 0; 55 | } 56 | 57 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/examples/elliptic.py: -------------------------------------------------------------------------------- 1 | """ 2 | Copyright 2009-2012 Karsten Ahnert 3 | Copyright 2009-2012 Mario Mulansky 4 | 5 | Stochastic euler stepper example and Ornstein-Uhlenbeck process 6 | 7 | Distributed under the Boost Software License, Version 1.0. 8 | (See accompanying file LICENSE_1_0.txt or 9 | copy at http://www.boost.org/LICENSE_1_0.txt) 10 | """ 11 | 12 | 13 | from pylab import * 14 | from scipy import special 15 | 16 | data1 = loadtxt("elliptic1.dat") 17 | data2 = loadtxt("elliptic2.dat") 18 | data3 = loadtxt("elliptic3.dat") 19 | 20 | sn1,cn1,dn1,phi1 = special.ellipj( data1[:,0] , 0.51 ) 21 | sn2,cn2,dn2,phi2 = special.ellipj( data2[:,0] , 0.51 ) 22 | sn3,cn3,dn3,phi3 = special.ellipj( data3[:,0] , 0.51 ) 23 | 24 | semilogy( data1[:,0] , abs(data1[:,1]-sn1) ) 25 | semilogy( data2[:,0] , abs(data2[:,1]-sn2) , 'ro' ) 26 | semilogy( data3[:,0] , abs(data3[:,1]-sn3) , '--' ) 27 | 28 | show() 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/examples/mtl/Jamfile.v2: -------------------------------------------------------------------------------- 1 | # Copyright 2009 Karsten Ahnert and Mario Mulansky. 2 | # Distributed under the Boost Software License, Version 1.0. (See 3 | # accompanying file LICENSE_1_0.txt or copy at 4 | # http://www.boost.org/LICENSE_1_0.txt) 5 | 6 | MTL4_INCLUDE = /home/karsten/boost/MTL-4.0.8862-Linux/usr/include ; 7 | 8 | project 9 | : requirements 10 | ../../../../.. 11 | $(MTL4_INCLUDE) 12 | BOOST_ALL_NO_LIB=1 13 | ; 14 | 15 | exe gauss_packet : gauss_packet.cpp ; 16 | exe implicit_euler_mtl : implicit_euler_mtl.cpp ; -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/examples/quadmath/Jamfile.v2: -------------------------------------------------------------------------------- 1 | # Copyright 2009 Karsten Ahnert and Mario Mulansky. 2 | # Distributed under the Boost Software License, Version 1.0. (See 3 | # accompanying file LICENSE_1_0.txt or copy at 4 | # http://www.boost.org/LICENSE_1_0.txt) 5 | 6 | 7 | project 8 | : requirements 9 | ../../../.. 10 | BOOST_ALL_NO_LIB=1 11 | : 12 | ; 13 | 14 | lib quadmath : : quadmath shared ; 15 | 16 | exe black_hole : black_hole.cpp quadmath : -std=c++0x ; -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/examples/simple1d.cpp: -------------------------------------------------------------------------------- 1 | /* Boost libs/numeric/odeint/examples/simple1d.cpp 2 | 3 | Copyright 2009-2012 Karsten Ahnert 4 | Copyright 2009-2012 Mario Mulansky 5 | 6 | example for a simple one-dimensional 1st order ODE 7 | 8 | Distributed under the Boost Software License, Version 1.0. 9 | (See accompanying file LICENSE_1_0.txt or 10 | copy at http://www.boost.org/LICENSE_1_0.txt) 11 | */ 12 | 13 | 14 | #include 15 | #include 16 | 17 | using namespace std; 18 | using namespace boost::numeric::odeint; 19 | 20 | 21 | /* we solve the simple ODE x' = 3/(2t^2) + x/(2t) 22 | * with initial condition x(1) = 0. 23 | * Analytic solution is x(t) = sqrt(t) - 1/t 24 | */ 25 | 26 | void rhs( const double x , double &dxdt , const double t ) 27 | { 28 | dxdt = 3.0/(2.0*t*t) + x/(2.0*t); 29 | } 30 | 31 | void write_cout( const double &x , const double t ) 32 | { 33 | cout << t << '\t' << x << endl; 34 | } 35 | 36 | // state_type = value_type = deriv_type = time_type = double 37 | typedef runge_kutta_dopri5< double , double , double , double , vector_space_algebra , default_operations , never_resizer > stepper_type; 38 | 39 | int main() 40 | { 41 | double x = 0.0; //initial value x(1) = 0 42 | // use dopri5 with stepsize control and allowed errors 10^-12, integrate t=1...10 43 | integrate_adaptive( make_controlled( 1E-12 , 1E-12 , stepper_type() ) , rhs , x , 1.0 , 10.0 , 0.1 , write_cout ); 44 | } 45 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/examples/ublas/Jamfile.v2: -------------------------------------------------------------------------------- 1 | # Copyright 2009 Karsten Ahnert and Mario Mulansky. 2 | # Distributed under the Boost Software License, Version 1.0. (See 3 | # accompanying file LICENSE_1_0.txt or copy at 4 | # http://www.boost.org/LICENSE_1_0.txt) 5 | 6 | 7 | project 8 | : requirements 9 | ../../../../.. 10 | BOOST_ALL_NO_LIB=1 11 | ; 12 | 13 | exe lorenz_ublas : lorenz_ublas.cpp ; 14 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/examples/ublas/lorenz_ublas.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2009-2012 Karsten Ahnert 3 | * Copyright 2009-2012 Mario Mulansky 4 | * 5 | * Distributed under the Boost Software License, Version 1.0. 6 | * (See accompanying file LICENSE_1_0.txt or 7 | * copy at http://www.boost.org/LICENSE_1_0.txt) 8 | */ 9 | 10 | 11 | #include 12 | 13 | #include 14 | #include 15 | 16 | /* define ublas::vector as resizeable 17 | * this is not neccessarily required because this definition already 18 | * exists in util/ublas_wrapper.hpp. 19 | * However, for completeness and educational purpose it is repeated here. 20 | */ 21 | 22 | //[ ublas_resizeable 23 | typedef boost::numeric::ublas::vector< double > state_type; 24 | 25 | namespace boost { namespace numeric { namespace odeint { 26 | 27 | template<> 28 | struct is_resizeable< state_type > 29 | { 30 | typedef boost::true_type type; 31 | const static bool value = type::value; 32 | }; 33 | 34 | } } } 35 | //] 36 | 37 | void lorenz( const state_type &x , state_type &dxdt , const double t ) 38 | { 39 | const double sigma( 10.0 ); 40 | const double R( 28.0 ); 41 | const double b( 8.0 / 3.0 ); 42 | 43 | dxdt[0] = sigma * ( x[1] - x[0] ); 44 | dxdt[1] = R * x[0] - x[1] - x[0] * x[2]; 45 | dxdt[2] = -b * x[2] + x[0] * x[1]; 46 | } 47 | 48 | using namespace boost::numeric::odeint; 49 | 50 | //[ublas_main 51 | int main() 52 | { 53 | state_type x(3); 54 | x[0] = 10.0; x[1] = 5.0 ; x[2] = 0.0; 55 | typedef runge_kutta4< state_type , double , state_type , double , vector_space_algebra > stepper; 56 | integrate_const( stepper() , lorenz , x , 57 | 0.0 , 10.0 , 0.1 ); 58 | } 59 | //] 60 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/examples/vexcl/Jamfile.v2: -------------------------------------------------------------------------------- 1 | # Copyright 2009-2012 Karsten Ahnert 2 | # Copyright 2009-2012 Mario Mulansky 3 | # 4 | # Distributed under the Boost Software License, Version 1.0. 5 | # (See accompanying file LICENSE_1_0.txt or 6 | # copy at http://www.boost.org/LICENSE_1_0.txt) 7 | 8 | 9 | import boost ; 10 | import os ; 11 | 12 | boost.use-project ; 13 | 14 | 15 | # change these lines to fit you configuration 16 | local HOME = [ os.environ HOME ] ; 17 | VEXCL_INCLUDE = $(HOME)/boost/vexcl ; 18 | CUDA_INCLUDE = /usr/local/cuda/include ; 19 | 20 | 21 | lib opencl : : OpenCL ; 22 | 23 | project : requirements 24 | /boost//headers 25 | ../../../../.. 26 | $(VEXCL_INCLUDE) 27 | $(CUDA_INCLUDE) 28 | gcc:-std=c++0x 29 | ; 30 | 31 | exe lorenz_ensemble : lorenz_ensemble.cpp opencl ; -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/index.html: -------------------------------------------------------------------------------- 1 | 6 | 7 | 8 | 9 | 10 | 11 | Automatic redirection failed, please go to 12 | doc/html/index.html 13 |
14 |

© Copyright Beman Dawes, 2001

15 |

Distributed under the Boost Software 16 | License, Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at 17 | www.boost.org/LICENSE_1_0.txt)

18 | 19 | 20 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/performance/gsl_rk4_lorenz.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * gsl_rk4_lorenz.cpp 3 | * 4 | * Copyright 2009-2012 Karsten Ahnert 5 | * Copyright 2009-2012 Mario Mulansky 6 | * 7 | * Distributed under the Boost Software License, Version 1.0. 8 | * (See accompanying file LICENSE_1_0.txt or 9 | * copy at http://www.boost.org/LICENSE_1_0.txt) 10 | */ 11 | 12 | 13 | #include 14 | 15 | #include "rk_performance_test_case.hpp" 16 | 17 | #include "lorenz_gsl.hpp" 18 | 19 | const size_t dim = 3; 20 | 21 | class gsl_wrapper 22 | { 23 | public: 24 | 25 | gsl_wrapper() 26 | { 27 | m_s = gsl_odeiv_step_alloc( gsl_odeiv_step_rk4 , dim); 28 | m_sys.function = lorenz_gsl; 29 | m_sys.jacobian = 0; 30 | m_sys.dimension = dim; 31 | m_sys.params = 0; 32 | } 33 | 34 | void reset_init_cond() 35 | { 36 | m_x[0] = 10.0 * rand() / RAND_MAX; 37 | m_x[1] = 10.0 * rand() / RAND_MAX; 38 | m_x[2] = 10.0 * rand() / RAND_MAX; 39 | m_t = 0.0; 40 | } 41 | 42 | inline void do_step( const double dt ) 43 | { 44 | gsl_odeiv_step_apply ( m_s , m_t , dt , m_x , m_x_err , 0 , 0 , &m_sys ); 45 | //m_t += dt; 46 | } 47 | 48 | double state( const size_t i ) const 49 | { return m_x[i]; } 50 | 51 | ~gsl_wrapper() 52 | { 53 | gsl_odeiv_step_free( m_s ); 54 | } 55 | 56 | private: 57 | double m_x[dim]; 58 | double m_x_err[dim]; 59 | double m_t; 60 | gsl_odeiv_step *m_s; 61 | gsl_odeiv_system m_sys; 62 | }; 63 | 64 | 65 | 66 | int main() 67 | { 68 | gsl_wrapper stepper; 69 | 70 | run( stepper , 20000000 / 3 , 1E-10 * 3); 71 | } 72 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/performance/lorenz.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * lorenz.hpp 3 | * 4 | * Copyright 2009-2012 Karsten Ahnert 5 | * Copyright 2009-2012 Mario Mulansky 6 | * 7 | * Distributed under the Boost Software License, Version 1.0. 8 | * (See accompanying file LICENSE_1_0.txt or 9 | * copy at http://www.boost.org/LICENSE_1_0.txt) 10 | */ 11 | 12 | 13 | #ifndef LORENZ_HPP_ 14 | #define LORENZ_HPP_ 15 | 16 | #include 17 | 18 | struct lorenz 19 | { 20 | template< class state_type > 21 | void inline operator()( const state_type &x , state_type &dxdt , const double t ) const 22 | { 23 | const double sigma = 10.0; 24 | const double R = 28.0; 25 | const double b = 8.0 / 3.0; 26 | dxdt[0] = sigma * ( x[1] - x[0] ); 27 | dxdt[1] = R * x[0] - x[1] - x[0] * x[2]; 28 | dxdt[2] = x[0]*x[1] - b * x[2]; 29 | } 30 | }; 31 | 32 | 33 | typedef boost::array< double , 3 > state_type; 34 | 35 | 36 | inline void lorenz_func( const state_type &x , state_type &dxdt , const double t ) 37 | { 38 | const double sigma = 10.0; 39 | const double R = 28.0; 40 | const double b = 8.0 / 3.0; 41 | dxdt[0] = sigma * ( x[1] - x[0] ); 42 | dxdt[1] = R * x[0] - x[1] - x[0] * x[2]; 43 | dxdt[2] = x[0]*x[1] - b * x[2]; 44 | } 45 | 46 | #endif /* LORENZ_HPP_ */ 47 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/performance/lorenz_gsl.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * lorenz_gsl.hpp 3 | * 4 | * Copyright 2009-2012 Karsten Ahnert 5 | * Copyright 2009-2012 Mario Mulansky 6 | * 7 | * Distributed under the Boost Software License, Version 1.0. 8 | * (See accompanying file LICENSE_1_0.txt or 9 | * copy at http://www.boost.org/LICENSE_1_0.txt) 10 | */ 11 | 12 | 13 | #ifndef LORENZ_GSL_HPP_ 14 | #define LORENZ_GSL_HPP_ 15 | 16 | #include 17 | 18 | int lorenz_gsl( const double t , const double y[] , double f[] , void *params) 19 | { 20 | const double sigma = 10.0; 21 | const double R = 28.0; 22 | const double b = 8.0 / 3.0; 23 | 24 | f[0] = sigma * ( y[1] - y[0] ); 25 | f[1] = R * y[0] - y[1] - y[0] * y[2]; 26 | f[2] = y[0]*y[1] - b * y[2]; 27 | return GSL_SUCCESS; 28 | } 29 | 30 | #endif 31 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/performance/odeint_rk4_lorenz_range.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * odeint_rk4_lorenz_def_alg.cpp 3 | * 4 | * Copyright 2009-2012 Karsten Ahnert 5 | * Copyright 2009-2012 Mario Mulansky 6 | * 7 | * Distributed under the Boost Software License, Version 1.0. 8 | * (See accompanying file LICENSE_1_0.txt or 9 | * copy at http://www.boost.org/LICENSE_1_0.txt) 10 | */ 11 | 12 | 13 | #include 14 | 15 | #include 16 | #include 17 | 18 | #include "rk_performance_test_case.hpp" 19 | 20 | #include "lorenz.hpp" 21 | 22 | typedef boost::array< double , 3 > state_type; 23 | typedef boost::numeric::odeint::runge_kutta4_classic< state_type > rk4_odeint_type; 24 | 25 | 26 | class odeint_wrapper 27 | { 28 | public: 29 | void reset_init_cond() 30 | { 31 | m_x[0] = 10.0 * rand() / RAND_MAX; 32 | m_x[1] = 10.0 * rand() / RAND_MAX; 33 | m_x[2] = 10.0 * rand() / RAND_MAX; 34 | m_t = 0.0; 35 | } 36 | 37 | inline void do_step( const double dt ) 38 | { 39 | m_stepper.do_step( lorenz() , m_x , m_t , dt ); 40 | //m_t += dt; 41 | } 42 | 43 | double state( const size_t i ) const 44 | { return m_x[i]; } 45 | 46 | private: 47 | state_type m_x; 48 | double m_t; 49 | rk4_odeint_type m_stepper; 50 | }; 51 | 52 | 53 | 54 | int main() 55 | { 56 | odeint_wrapper stepper; 57 | 58 | run( stepper ); 59 | } 60 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/performance/odeint_rk4_phase_lattice.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * odeint_rk4_phase_lattice.cpp 3 | * 4 | * Copyright 2009-2012 Karsten Ahnert 5 | * Copyright 2009-2012 Mario Mulansky 6 | * 7 | * Distributed under the Boost Software License, Version 1.0. 8 | * (See accompanying file LICENSE_1_0.txt or 9 | * copy at http://www.boost.org/LICENSE_1_0.txt) 10 | */ 11 | 12 | 13 | #include 14 | 15 | #include 16 | 17 | #include 18 | #include 19 | #include 20 | 21 | #include "rk_performance_test_case.hpp" 22 | 23 | #include "phase_lattice.hpp" 24 | 25 | const size_t N = 1024; 26 | 27 | typedef boost::array< double , N > state_type; 28 | typedef boost::numeric::odeint::runge_kutta4_classic< state_type , double , state_type , double , boost::numeric::odeint::array_algebra> rk4_odeint_type; 29 | 30 | class odeint_wrapper 31 | { 32 | public: 33 | void reset_init_cond() 34 | { 35 | for( size_t i = 0 ; i() , m_x , m_t , dt ); 43 | //m_t += dt; 44 | } 45 | 46 | double state( const size_t i ) const 47 | { return m_x[i]; } 48 | 49 | private: 50 | state_type m_x; 51 | double m_t; 52 | rk4_odeint_type m_stepper; 53 | }; 54 | 55 | 56 | 57 | int main() 58 | { 59 | srand( 12312354 ); 60 | 61 | odeint_wrapper stepper; 62 | 63 | run( stepper , 10000 , 1E-6 ); 64 | } 65 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/performance/phase_lattice.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2009-2012 Karsten Ahnert 3 | * Copyright 2009-2012 Mario Mulansky 4 | * 5 | * Distributed under the Boost Software License, Version 1.0. 6 | * (See accompanying file LICENSE_1_0.txt or 7 | * copy at http://www.boost.org/LICENSE_1_0.txt) 8 | */ 9 | 10 | #include 11 | 12 | #include 13 | 14 | template< size_t N > 15 | struct phase_lattice 16 | { 17 | typedef double value_type; 18 | typedef boost::array< value_type , N > state_type; 19 | 20 | value_type m_epsilon; 21 | state_type m_omega; 22 | 23 | phase_lattice() : m_epsilon( 6.0/(N*N) ) // should be < 8/N^2 to see phase locking 24 | { 25 | for( size_t i=1 ; i 19 | 20 | #include 21 | #include 22 | #include 23 | 24 | template< size_t N > 25 | struct phase_lattice_mkl 26 | { 27 | typedef double value_type; 28 | typedef boost::array< value_type , N > state_type; 29 | 30 | value_type m_epsilon; 31 | state_type m_omega; 32 | state_type m_tmp; 33 | 34 | phase_lattice_mkl() : m_epsilon( 6.0/(N*N) ) // should be < 8/N^2 to see phase locking 35 | { 36 | for( size_t i=1 ; i 12 | 13 | using namespace std; 14 | 15 | struct rt_algebra 16 | { 17 | template< typename T , size_t dim > 18 | inline static void foreach( boost::array< T , dim > & x_tmp , 19 | const boost::array< T , dim > &x , 20 | //const vector< double > &a , 21 | const double* a , 22 | const boost::array< T , dim > *k_vector , 23 | const double dt , const size_t s ) 24 | { 25 | for( size_t i=0 ; i/boost/test//boost_unit_test_framework 15 | BOOST_ALL_NO_LIB=1 16 | ../../../.. 17 | static 18 | clang:-Wno-unused-variable 19 | 20 | # -D_SCL_SECURE_NO_WARNINGS 21 | ; 22 | 23 | test-suite "odeint" 24 | : 25 | [ run euler_stepper.cpp ] 26 | [ run runge_kutta_concepts.cpp ] 27 | [ run runge_kutta_error_concepts.cpp ] 28 | [ run runge_kutta_controlled_concepts.cpp ] 29 | [ run resizing.cpp ] 30 | [ run default_operations.cpp ] 31 | [ run range_algebra.cpp ] 32 | [ run implicit_euler.cpp ] 33 | [ run fusion_algebra.cpp ] 34 | [ run stepper_with_units.cpp ] 35 | [ run stepper_copying.cpp ] 36 | [ run stepper_with_ranges.cpp ] 37 | [ run rosenbrock4.cpp ] 38 | [ run is_pair.cpp ] 39 | [ run adams_bashforth.cpp ] 40 | [ run adams_moulton.cpp ] 41 | [ run adams_bashforth_moulton.cpp ] 42 | [ run generic_stepper.cpp ] 43 | [ run generic_error_stepper.cpp ] 44 | [ run bulirsch_stoer.cpp ] 45 | [ run integrate_times.cpp ] 46 | [ run integrate.cpp ] 47 | [ run integrate_implicit.cpp ] 48 | [ run generation.cpp ] 49 | [ run trivial_state.cpp ] 50 | [ run is_resizeable.cpp ] 51 | [ run resize.cpp ] 52 | [ run same_size.cpp ] 53 | [ run symplectic_steppers.cpp ] 54 | : valgrind 55 | ; 56 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/test/const_range.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | libs/numeric/odeint/test/const_range.hpp 4 | 5 | [begin_description] 6 | tba. 7 | [end_description] 8 | 9 | Copyright 2009-2012 Karsten Ahnert 10 | Copyright 2009-2012 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | 18 | #ifndef LIBS_NUMERIC_ODEINT_TEST_CONST_RANGE_HPP_DEFINED 19 | #define LIBS_NUMERIC_ODEINT_TEST_CONST_RANGE_HPP_DEFINED 20 | 21 | #include 22 | #include 23 | #include 24 | #include 25 | #include 26 | #include 27 | #include 28 | 29 | 30 | namespace mpl = boost::mpl; 31 | 32 | 33 | 34 | template< class N , class T > 35 | struct const_range 36 | { 37 | typedef typename mpl::copy< 38 | mpl::range_c< typename N::value_type , 0 , N::value > , 39 | mpl::inserter< 40 | mpl::vector0<> , 41 | mpl::insert< 42 | mpl::_1 , 43 | mpl::end< mpl::_1 > , 44 | T 45 | > 46 | > 47 | >::type type; 48 | }; 49 | 50 | #endif // LIBS_NUMERIC_ODEINT_TEST_CONST_RANGE_HPP_DEFINED 51 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/test/is_pair.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | libs/numeric/odeint/test/is_pair.cpp 4 | 5 | [begin_description] 6 | This file tests the is_pair meta-function. 7 | [end_description] 8 | 9 | Copyright 2009-2012 Karsten Ahnert 10 | Copyright 2009-2012 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | #define BOOST_TEST_MODULE odeint_is_pair 18 | 19 | #include 20 | 21 | #include 22 | #include 23 | 24 | #include 25 | 26 | using namespace boost::numeric::odeint; 27 | 28 | 29 | 30 | BOOST_AUTO_TEST_SUITE( is_pair_test ) 31 | 32 | BOOST_AUTO_TEST_CASE( test_is_pair ) 33 | { 34 | typedef std::pair< int , int > type1; 35 | typedef std::pair< int& , int > type2; 36 | typedef std::pair< int , int& > type3; 37 | typedef std::pair< int& , int& > type4; 38 | typedef std::pair< const int , int > type5; 39 | typedef std::pair< const int& , int > type6; 40 | 41 | BOOST_STATIC_ASSERT(( is_pair< type1 >::value )); 42 | BOOST_STATIC_ASSERT(( is_pair< type2 >::value )); 43 | BOOST_STATIC_ASSERT(( is_pair< type3 >::value )); 44 | BOOST_STATIC_ASSERT(( is_pair< type4 >::value )); 45 | BOOST_STATIC_ASSERT(( is_pair< type5 >::value )); 46 | BOOST_STATIC_ASSERT(( is_pair< type6 >::value )); 47 | } 48 | 49 | BOOST_AUTO_TEST_SUITE_END() 50 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/test/numeric/Jamfile.v2: -------------------------------------------------------------------------------- 1 | # (C) Copyright 2010 : Karsten Ahnert, Mario Mulansky 2 | # Distributed under the Boost Software License, Version 1.0. 3 | # (See accompanying file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 4 | 5 | # bring in rules for testing 6 | 7 | 8 | import testing ; 9 | 10 | use-project boost : $(BOOST_ROOT) ; 11 | 12 | project 13 | : requirements 14 | /boost/test//boost_unit_test_framework 15 | BOOST_ALL_NO_LIB=1 16 | ../../../.. 17 | static 18 | clang:-Wno-unused-variable 19 | 20 | # -D_SCL_SECURE_NO_WARNINGS 21 | ; 22 | 23 | test-suite "odeint" 24 | : 25 | [ run runge_kutta.cpp ] 26 | [ run symplectic.cpp ] 27 | [ run rosenbrock.cpp ] 28 | : valgrind 29 | ; 30 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/test/same_size.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | [auto_generated] 3 | libs/numeric/odeint/test/same_size.cpp 4 | 5 | [begin_description] 6 | tba. 7 | [end_description] 8 | 9 | Copyright 2009-2012 Karsten Ahnert 10 | Copyright 2009-2012 Mario Mulansky 11 | 12 | Distributed under the Boost Software License, Version 1.0. 13 | (See accompanying file LICENSE_1_0.txt or 14 | copy at http://www.boost.org/LICENSE_1_0.txt) 15 | */ 16 | 17 | #include 18 | #ifdef BOOST_MSVC 19 | #pragma warning(disable:4996) 20 | #endif 21 | 22 | #define BOOST_TEST_MODULE odeint_dummy 23 | 24 | #include 25 | 26 | #include 27 | 28 | using namespace boost::unit_test; 29 | using namespace boost::numeric::odeint; 30 | 31 | 32 | BOOST_AUTO_TEST_SUITE( same_size_test ) 33 | 34 | BOOST_AUTO_TEST_CASE( test_vector_true ) 35 | { 36 | std::vector< double > v1( 10 ) , v2( 10 ); 37 | BOOST_CHECK_EQUAL( true , same_size( v1 , v2 ) ); 38 | } 39 | 40 | 41 | BOOST_AUTO_TEST_CASE( test_vector_false ) 42 | { 43 | std::vector< double > v1( 10 ) , v2( 20 ); 44 | BOOST_CHECK_EQUAL( false , same_size( v1 , v2 ) ); 45 | } 46 | 47 | BOOST_AUTO_TEST_CASE( test_fusion_true ) 48 | { 49 | boost::fusion::vector< double , std::vector< double > > v1 , v2; 50 | boost::fusion::at_c< 1 >( v1 ).resize( 10 ); 51 | boost::fusion::at_c< 1 >( v2 ).resize( 10 ); 52 | BOOST_CHECK_EQUAL( true , same_size( v1 , v2 ) ); 53 | } 54 | 55 | BOOST_AUTO_TEST_CASE( test_fusion_false ) 56 | { 57 | boost::fusion::vector< double , std::vector< double > > v1 , v2; 58 | boost::fusion::at_c< 1 >( v1 ).resize( 10 ); 59 | boost::fusion::at_c< 1 >( v2 ).resize( 20 ); 60 | BOOST_CHECK_EQUAL( false , same_size( v1 , v2 ) ); 61 | } 62 | 63 | 64 | 65 | BOOST_AUTO_TEST_SUITE_END() 66 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/test_external/gmp/Jamfile.v2: -------------------------------------------------------------------------------- 1 | # (C) Copyright 2010 : Karsten Ahnert, Mario Mulansky 2 | # Distributed under the Boost Software License, Version 1.0. 3 | # (See accompanying file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 4 | 5 | # bring in rules for testing 6 | 7 | import testing ; 8 | use-project boost : $(BOOST_ROOT) ; 9 | 10 | project gmp 11 | : requirements 12 | /boost/test//boost_unit_test_framework 13 | ../../../../.. 14 | ; 15 | 16 | 17 | lib libgmp : : gmp shared ; 18 | lib libgmpxx : : gmpxx shared ; 19 | 20 | test-suite "gmp" 21 | : 22 | [ run check_gmp.cpp libgmpxx libgmp : : : shared:BOOST_TEST_DYN_LINK=1 ] 23 | [ run gmp_integrate.cpp libgmpxx libgmp : : : shared:BOOST_TEST_DYN_LINK=1 ] 24 | ; 25 | 26 | 27 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/test_external/gsl/Jamfile.v2: -------------------------------------------------------------------------------- 1 | # (C) Copyright 2010 : Karsten Ahnert, Mario Mulansky 2 | # Distributed under the Boost Software License, Version 1.0. 3 | # (See accompanying file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 4 | 5 | # bring in rules for testing 6 | 7 | import testing ; 8 | use-project boost : $(BOOST_ROOT) ; 9 | 10 | project 11 | : requirements 12 | /boost/test//boost_unit_test_framework 13 | ../../../../.. 14 | ; 15 | 16 | 17 | lib libgsl : : gsl shared ; 18 | lib libgslcblas : : gslcblas shared ; 19 | 20 | test-suite "gsl" 21 | : 22 | [ run check_gsl.cpp libgslcblas libgsl 23 | : 24 | : 25 | : shared:BOOST_TEST_DYN_LINK=1 26 | ] 27 | ; 28 | 29 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/test_external/gsl/check_gsl.cpp: -------------------------------------------------------------------------------- 1 | /* Boost check_gmp.cpp test file 2 | 3 | Copyright 2009 Karsten Ahnert 4 | Copyright 2009 Mario Mulansky 5 | 6 | This file tests the odeint library with the gmp arbitrary precision types 7 | 8 | Distributed under the Boost Software License, Version 1.0. 9 | (See accompanying file LICENSE_1_0.txt or 10 | copy at http://www.boost.org/LICENSE_1_0.txt) 11 | */ 12 | 13 | #define BOOST_TEST_MODULE odeint_gsl 14 | 15 | #include 16 | #include 17 | #include 18 | 19 | #include 20 | 21 | using namespace boost::unit_test; 22 | using namespace boost::numeric::odeint; 23 | 24 | typedef gsl_vector *state_type; 25 | 26 | const double sigma = 10.0; 27 | const double R = 28.0; 28 | const double b = 8.0 / 3.0; 29 | 30 | void lorenz( const state_type x , state_type dxdt , double t ) 31 | { 32 | gsl_vector_set( dxdt , 0 , sigma * ( gsl_vector_get(x , 1 ) - gsl_vector_get( x , 0 ) ) ); 33 | gsl_vector_set( dxdt , 1 , R * gsl_vector_get( x , 0 ) - gsl_vector_get( x , 1 ) - gsl_vector_get( x , 0 ) * gsl_vector_get( x , 2) ); 34 | gsl_vector_set( dxdt , 2 , gsl_vector_get( x , 0 ) * gsl_vector_get( x , 1 ) - b * gsl_vector_get( x , 2) ); 35 | } 36 | 37 | BOOST_AUTO_TEST_CASE( gsl ) 38 | { 39 | euler< state_type > euler; 40 | 41 | state_type x = gsl_vector_alloc( 3 ); 42 | gsl_vector_set( x , 0 , 1.0); 43 | gsl_vector_set( x , 1 , 1.0); 44 | gsl_vector_set( x , 2 , 2.0); 45 | 46 | euler.do_step( lorenz , x , 0.0 , 0.1 ); 47 | 48 | //cout << gsl_vector_get( x , 0 ) << " " << gsl_vector_get( x , 1 ) << " " << gsl_vector_get( x , 2 ) << endl; 49 | 50 | gsl_vector_free( x ); 51 | 52 | } 53 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/test_external/mkl/Jamfile.v2: -------------------------------------------------------------------------------- 1 | # (C) Copyright 2010 : Karsten Ahnert, Mario Mulansky 2 | # Distributed under the Boost Software License, Version 1.0. 3 | # (See accompanying file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 4 | 5 | # bring in rules for testing 6 | 7 | import testing ; 8 | use-project boost : $(BOOST_ROOT) ; 9 | 10 | project 11 | : requirements 12 | /boost/test//boost_unit_test_framework 13 | ../../../../.. 14 | ; 15 | 16 | 17 | lib libmkl : : mkl_intel_lp64 shared ; 18 | lib libmkl_core : : mkl_core shared ; 19 | lib libmkl_intel_thread : : mkl_intel_thread ; 20 | lib libiomp5 : : iomp5 ; 21 | lib libpthread : : pthread ; 22 | 23 | test-suite "mkl" 24 | : 25 | [ run check_mkl.cpp libpthread libiomp5 libmkl_core libmkl_intel_thread libmkl 26 | : 27 | : 28 | : shared:BOOST_TEST_DYN_LINK=1 29 | ] 30 | ; 31 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/test_external/mkl/check_mkl.cpp: -------------------------------------------------------------------------------- 1 | /* Boost check_mkl.cpp test file 2 | 3 | Copyright 2009 Karsten Ahnert 4 | Copyright 2009 Mario Mulansky 5 | 6 | This file tests the odeint library with the intel mkl blas1 routines 7 | 8 | Distributed under the Boost Software License, Version 1.0. 9 | (See accompanying file LICENSE_1_0.txt or 10 | copy at http://www.boost.org/LICENSE_1_0.txt) 11 | */ 12 | 13 | #define BOOST_TEST_MODULE test_mkl 14 | 15 | #include 16 | 17 | #include 18 | #include 19 | #include 20 | #include 21 | 22 | using namespace boost::numeric::odeint; 23 | 24 | typedef double value_type; 25 | typedef boost::array< value_type , 1 > state_type; 26 | 27 | 28 | void constant_system( state_type &x , state_type &dxdt , value_type t ) 29 | { 30 | dxdt[0] = 1.0; 31 | } 32 | 33 | const double eps = 1E-14; 34 | 35 | 36 | BOOST_AUTO_TEST_CASE( test_mkl ) 37 | { 38 | 39 | //to use mkl routines we have to use the vector_space_algebra and the mkl_operations 40 | runge_kutta4< state_type , value_type , state_type , value_type , vector_space_algebra , mkl_operations > stepper; 41 | state_type x; 42 | x[0] = 0.0; 43 | 44 | stepper.do_step( constant_system , x , 0.0 , 0.1 ); 45 | 46 | using std::abs; 47 | 48 | std::cout << x[0] << " ?= " << 0.1 << std::endl; 49 | BOOST_CHECK_SMALL( abs( x[0] - 0.1 ) , eps ); 50 | 51 | } 52 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/test_external/mtl4/Jamfile.v2: -------------------------------------------------------------------------------- 1 | # Copyright 2009 Karsten Ahnert and Mario Mulansky. 2 | # Distributed under the Boost Software License, Version 1.0. (See 3 | # accompanying file LICENSE_1_0.txt or copy at 4 | # http://www.boost.org/LICENSE_1_0.txt) 5 | 6 | import testing ; 7 | import boost ; 8 | 9 | boost.use-project ; 10 | 11 | MTL4_INCLUDE = /home/karsten/boost/MTL-4.0.8862-Linux/usr/include ; 12 | 13 | project 14 | : requirements 15 | /boost/test//boost_unit_test_framework 16 | ../../../../.. 17 | $(MTL4_INCLUDE) 18 | BOOST_ALL_NO_LIB=1 19 | static 20 | : 21 | : default-build release 22 | ; 23 | 24 | test-suite "odeint-mtl4" 25 | : 26 | [ run mtl4_resize.cpp ] 27 | : valgrind 28 | ; 29 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/test_external/thrust/Makefile: -------------------------------------------------------------------------------- 1 | # Copyright 2009-2012 Karsten Ahnert 2 | # Copyright 2009-2012 Mario Mulansky 3 | # 4 | # Distributed under the Boost Software License, Version 1.0. 5 | # (See accompanying file LICENSE_1_0.txt or 6 | # copy at http://www.boost.org/LICENSE_1_0.txt) 7 | 8 | 9 | 10 | CUDA_ROOT = /usr/local/cuda 11 | 12 | CC = gcc-4.4 13 | CXX = gcc-4.4 14 | NVCC = $(CUDA_ROOT)/bin/nvcc 15 | 16 | INCLUDES += -I$(BOOST_ROOT) -I$(THRUST_ROOT) -I$(CUDA_ROOT)/include -I../../../../.. 17 | 18 | NVCCFLAGS = -O3 $(INCLUDES) --compiler-bindir=/usr/bin/g++-4.4 19 | 20 | LDLIBS = -lcudart 21 | LDFLAGS = -L$(CUDA_ROOT)/lib64 22 | 23 | %.co : %.cu 24 | $(NVCC) $(NVCCFLAGS) -o $@ -c $< 25 | 26 | 27 | all : check_thrust 28 | 29 | 30 | check_thrust : check_thrust.co 31 | $(CC) -o check_thrust $(LDFLAGS) $(LDLIBS) check_thrust.co 32 | check_thrust.co : check_thrust.cu 33 | 34 | clean : 35 | -rm *~ *.o *.co check_thrust 36 | 37 | -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/include/ode/libs/numeric/odeint/test_external/vexcl/Jamfile.v2: -------------------------------------------------------------------------------- 1 | # (C) Copyright 2010 : Karsten Ahnert, Mario Mulansky 2 | # Distributed under the Boost Software License, Version 1.0. 3 | # (See accompanying file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 4 | 5 | # bring in rules for testing 6 | 7 | 8 | import testing ; 9 | 10 | use-project boost : $(BOOST_ROOT) ; 11 | VEXCL_INCLUDE = /home/karsten/boost/vexcl ; 12 | CUDA_INCLUDE = /usr/local/cuda/include ; 13 | 14 | 15 | project 16 | : requirements 17 | /boost/test//boost_unit_test_framework 18 | BOOST_ALL_NO_LIB=1 19 | ../../../../.. 20 | $(VEXCL_INCLUDE) 21 | $(CUDA_INCLUDE) 22 | -std=c++0x 23 | ; 24 | 25 | lib OpenCL : : OpenCL shared ; 26 | 27 | test-suite "odeint" 28 | : 29 | [ run lorenz.cpp OpenCL ] 30 | : valgrind 31 | : 32 | : shared:BOOST_TEST_DYN_LINK=1 33 | ; -------------------------------------------------------------------------------- /src/uav_simulator/so3_quadrotor_simulator/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 0.0.0 3 | so3_quadrotor_simulator 4 | 5 | 6 | quadrotor_simulator 7 | 8 | 9 | 10 | Kartik Mohta 11 | BSD 12 | http://ros.org/wiki/quadrotor_simulator 13 | 14 | catkin 15 | 16 | roscpp 17 | quadrotor_msgs 18 | uav_utils 19 | cmake_utils 20 | 21 | roscpp 22 | quadrotor_msgs 23 | uav_utils 24 | cmake_utils 25 | 26 | 27 | 28 | 29 | --------------------------------------------------------------------------------