Coder Social home page Coder Social logo

octomapplanner's Introduction

OctomapPlanner

This article explains how to set up and use ArduPlanner to work with Gazebo SITL

https://discuss.ardupilot.org/uploads/default/original/3X/f/1/f1618477d5558a5b77a186b81b52ae4e84345c09.jpg

Overview

OctomapPlanner is a library for autonomous mapping and planning specifically designed for ArduPilot Copter. It uses Octomap for 3D occupancy mapping and OMPL and FCL for goal-directed planning with collision avoidance.

This library is still under development and has only been tested to work with Gazebo SITL for limited test cases. Further development and tests on hardware are still to be done.

Setup Instructions

It is recommended to use Ubuntu 16.04 since all the tests have been conducted on it.

Make sure to install gazebo-8 instead of gazebo-7 since visualization messages are not supported before gazebo-8

Users should first setup OSRF keys and install Gazebo 8 by executing

sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
sudo apt update
sudo apt install libgazebo8-dev

We will also use ros sources for installing other dependencies. To do that use the following commands

sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116
sudo apt update

ROS users can also install Gazebo 8 with ROS support after adding OSRF keys and using ros-kinetic-gazebo8-* packages

Follow the steps here to install ardupilot_gazebo https://github.com/swiftgust/ardupilot_gazebo

Dependencies Installation

octomap

sudo apt install liboctomap-dev

mavlink

sudo apt install ros-kinetic-mavlink

OMPL

sudo apt install ros-kinetic-ompl

fcl

git clone https://github.com/danfis/libccd
cd libccd
mkdir build && cd build
cmake -G "Unix Makefiles" -DBUILD_SHARED_LIBS=ON ..
make && sudo make install

git clone https://github.com/flexible-collision-library/fcl
cd fcl
mkdir build
cd build
cmake ..
sudo make install

Finally, build OctomapPlanner and copy the iris model and grass model for gazebo to find

git clone https://github.com/ardupilot/OctomapPlanner
cd OctomapPlanner
mkdir build
cd build
cmake ..
make
cp -r ../models/* ~/.gazebo/models/

Running the code

Launch Gazebo with a demo world by executing

gazebo --verbose worlds/iris_gas_station_demo.world

On a seperate terminal start ArduCopter SITL

sim_vehicle.py -v ArduCopter -f gazebo-iris

Switch the copter to guided mode and takeoff using the following commands

mode guided
arm throttle
takeoff 1 (or any other hight in metres)

Before launching the code you may want to edit a few parameters like start and goal location This can be done by editing the planner_params.yaml file inside the config folder

Finally, launch the planner code by executing this from the OctomapPlanner root folder

./build/main_node

Related Blogs

GSoC 2018: Realtime Mapping and Planning for Collision Avoidance

GSoC 2018: Realtime Mapping and Planning for Collision Avoidance: Part 2

octomapplanner's People

Contributors

ayushgaud avatar swiftgust avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

octomapplanner's Issues

Question regarding Octomap & Planner

Hello,
I have set up cluttered environment and playing with this repository.
What I have set-up here is world with walls, bars and trees are up ahead but found not satisfactory result.
If planner works properly, drone can fly almost straight ahead with some small course correction

screenshot from 2019-01-14 15-14-45
image

I have managed StereoSGBM parameter little bit tuned.

PreFilterCap: 32
sgbmWinSize: 7
MinDisparity: 0
UniquenessRatio: 65
SpeckleWindowSize: 500
SpeckleRange: 1
Disp12MaxDiff: 1
TextureThreshold: 0
Width: 640
Height: 480
Scale: 1

In disparity map, I can clearly see obstacles with some noise, but Octomap result is quite different.
It is mapped as some radial way regarding walls in left & right front.
disparity_screenshot_14 01 2019

map.bt.tar.gz

And also I'm wondering that does InformedRRT* check how much space vehicle does occupy.
It plans like it tries to move through the wall if it finds small space in thick wall
and does not avoid bars so far.
However, it does pause in front of bars for few seconds then goes straight head into.

I'd like to know more about these issues so maybe I can help to improve.
Thank you.

error when executing ./build/main_node

hi, It went pretty well before ./build/main_node,when I executed the ./build/main_node, I got the following mistake:
main_node: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h:128: Eigen::internal::plain_array<T, Size, MatrixOrArrayOptions, 32>::plain_array() [with T = float; int Size = 16; int MatrixOrArrayOptions = 0]: Assertion `(internal::UIntPtr(eigen_unaligned_array_assert_workaround_gcc47(array)) & (31)) == 0 && "this assertion is explained here: " "http://eigen.tuxfamily.org/dox-devel/group__TopicUnalignedArrayAssert.html" " **** READ THIS WEB PAGE !!! ****"' failed.
Aborted (core dumped)

Can you help me with this issue?

seg fault

I have working ubuntu 18.04 / gazebo9 / ardupilot_gazebo / ros-melodic, but based on Pierre's setup (not swiftgus fork as per the readme here).
the planner segfaults as detailed:

/home/james/Development/OctomapPlanner/src/OctomapServer.cpp OctomapServer: Line 49: Octomap Initalized
Info:    InformedRRTstar: Space information setup was not yet called. Calling now.
Debug:   InformedRRTstar: Planner range detected to be 5.688585
/home/james/Development/OctomapPlanner/src/Planner.cpp Planner: Line 91: Planner Initialized
/home/james/Development/OctomapPlanner/src/mavlink_comm.cpp MavlinkComm: Line 56: Mavlink Initialized
/home/james/Development/OctomapPlanner/src/arduplanner.cpp executePlan: Line 220: No new plan available, waiting for 1 seconds before next callback
/home/james/Development/OctomapPlanner/src/arduplanner.cpp executePlan: Line 220: No new plan available, waiting for 1 seconds before next callback
/home/james/Development/OctomapPlanner/src/arduplanner.cpp executePlan: Line 220: No new plan available, waiting for 1 seconds before next callback
/home/james/Development/OctomapPlanner/src/arduplanner.cpp executePlan: Line 220: No new plan available, waiting for 1 seconds before next callback
/home/james/Development/OctomapPlanner/src/arduplanner.cpp executePlan: Line 220: No new plan available, waiting for 1 seconds before next callback
/home/james/Development/OctomapPlanner/src/arduplanner.cpp replanCb: Line 229: Replanner called
/home/james/Development/OctomapPlanner/src/Planner.cpp setGoal: Line 134: Goal point set to: 5 1 1
/home/james/Development/OctomapPlanner/src/Planner.cpp setStart: Line 112: Start point set to: -0.12129 -0.112817 5.00172
/home/james/Development/OctomapPlanner/src/Planner.cpp replan: Line 180: Replanning
Warning: InformedRRTstar: Skipping invalid start state (invalid bounds)
         at line 248 in /tmp/binarydeb/ros-melodic-ompl-1.4.0/src/ompl/base/src/Planner.cpp
Debug:   InformedRRTstar: Discarded start state RealVectorState [-0.12129 -0.112817 5.00172]

Error:   InformedRRTstar: There are no valid initial states!
         at line 193 in /tmp/binarydeb/ros-melodic-ompl-1.4.0/src/ompl/geometric/planners/rrt/src/RRTstar.cpp
/home/james/Development/OctomapPlanner/src/Planner.cpp plan: Line 216: No solution found
/home/james/Development/OctomapPlanner/src/arduplanner.cpp replanCb: Line 246: New plan generated
Segmentation fault (core dumped)
james@auturgy:~/Development/OctomapPlanner$ 

Error running gazebo --verbose worlds/iris_gas_station_demo.world

When I execute gazebo --verbose worlds/iris_gas_station_demo.world, the warning shown below is displayed.
image
My gazebo version is as follows

Gazebo multi-robot simulator, version 8.6.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

Gazebo multi-robot simulator, version 8.6.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

error when compiling main_node

/usr/bin/ld: warning: liboctomap.so.1.8, needed by libArduPlanner.so, may conflict with liboctomap.so.1.6
libPlanner.so:对‘fcl::CollisionGeometry::~CollisionGeometry()’未定义的引用
libPlanner.so:对‘fcl::CollisionObject::CollisionObject(std::shared_ptr<fcl::CollisionGeometry > const&)’未定义的引用
libPlanner.so:对‘unsigned long fcl::collide(fcl::CollisionObject const*, fcl::CollisionObject const*, fcl::CollisionRequest const&, fcl::CollisionResult&)’未定义的引用
libPlanner.so:对‘fcl::CollisionResult::isCollision() const’未定义的引用
libPlanner.so:对‘vtable for fcl::ShapeBase’未定义的引用
libPlanner.so:对‘fcl::OcTree::OcTree(std::shared_ptr<octomap::OcTree const> const&)’未定义的引用
libPlanner.so:对‘fcl::Box::Box(double, double, double)’未定义的引用
libPlanner.so:对‘fcl::CollisionRequest::CollisionRequest(unsigned long, bool, unsigned long, bool, bool, fcl::GJKSolverType, double)’未定义的引用
libPlanner.so:对‘fcl::CollisionObject::setTranslation(Eigen::Matrix<double, 3, 1, 0, 3, 1> const&)’未定义的引用
libPlanner.so:对‘fcl::CollisionObject::~CollisionObject()’未定义的引用
libPlanner.so:对‘fcl::CollisionResult::CollisionResult()’未定义的引用
collect2: error: ld returned 1 exit status
CMakeFiles/main_node.dir/build.make:433: recipe for target 'main_node' failed
make[2]: *** [main_node] Error 1
CMakeFiles/Makefile2:77: recipe for target 'CMakeFiles/main_node.dir/all' failed
make[1]: *** [CMakeFiles/main_node.dir/all] Error 2
Makefile:83: recipe for target 'all' failed
make: *** [all] Error 2

what is the fcl

I have't seen the fcl library, could you tell me what is the role in the project

Error when compiling "fcl"

When I execute the following code, I get an error when compiling the code.

git clone https://github.com/flexible-collision-library/fcl
cd fcl
mkdir build
cd build
cmake ..
sudo make install

The error message is as follows:

Scanning dependencies of target test_gjk_libccd-inl_epa [ 95%] Building CXX object test/narrowphase/detail/convexity_based_algorithm/CMakeFiles/test_gjk_libccd-inl_epa.dir/test_gjk_libccd-inl_epa.cpp.o In file included from /usr/include/eigen3/Eigen/Core:348:0, from /usr/include/eigen3/Eigen/Dense:1, from /home/baiyang/src/fcl/include/fcl/common/types.h:46, from /home/baiyang/src/fcl/include/fcl/math/bv/AABB.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/collision_geometry.h:43, from /home/baiyang/src/fcl/include/fcl/geometry/shape/shape_base.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/shape/box.h:41, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h:47, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h:41, from /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:42: /usr/include/eigen3/Eigen/src/Core/Product.h: In instantiation of ‘struct Eigen::internal::product_result_scalar<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, Eigen::DenseShape, Eigen::DenseShape>’: /usr/include/eigen3/Eigen/src/Core/Product.h:78:73: required from ‘struct Eigen::internal::traits<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >’ /usr/include/eigen3/Eigen/src/Core/Product.h:151:7: required from ‘class Eigen::internal::dense_product_base<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, 3>’ /usr/include/eigen3/Eigen/src/Core/Product.h:183:7: required from ‘class Eigen::ProductImpl<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, Eigen::Dense>’ /usr/include/eigen3/Eigen/src/Core/Product.h:107:7: required from ‘class Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0>’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:94:33: required from ‘Eigen::RotationBase<Derived, _Dim>::VectorType Eigen::RotationBase<Derived, _Dim>::_transformVector(const OtherVectorType&) const [with OtherVectorType = Eigen::Matrix<float, 3, 1>; Derived = Eigen::AngleAxis; int _Dim = 3; Eigen::RotationBase<Derived, _Dim>::VectorType = Eigen::Matrix<double, 3, 1>; typename Eigen::internal::traits::Scalar = double]’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:128:32: required from ‘static Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::ReturnType Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::run(const RotationDerived&, const OtherVectorType&) [with RotationDerived = Eigen::AngleAxis; OtherVectorType = Eigen::Matrix<float, 3, 1>; Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::ReturnType = Eigen::Matrix<double, 3, 1>; typename RotationDerived::Scalar = double]’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:72:89: required from ‘typename Eigen::internal::rotation_base_generic_product_selector<Derived, OtherDerived, OtherDerived:: IsVectorAtCompileTime>::ReturnType Eigen::RotationBase<Derived, _Dim>::operator*(const Eigen::EigenBase&) const [with OtherDerived = Eigen::Matrix<float, 3, 1>; Derived = Eigen::AngleAxis; int _Dim = 3; typename Eigen::internal::rotation_base_generic_product_selector<Derived, OtherDerived, OtherDerived:: IsVectorAtCompileTime>::ReturnType = Eigen::Matrix<double, 3, 1>]’ /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:242:40: required from here /usr/include/eigen3/Eigen/src/Core/Product.h:41:98: error: no type named ‘ReturnType’ in ‘struct Eigen::internal::scalar_product_traits<double, float>’ typedef typename scalar_product_traits<typename Lhs::Scalar, typename Rhs::Scalar>::ReturnType Scalar; ^ In file included from /usr/include/eigen3/Eigen/Core:344:0, from /usr/include/eigen3/Eigen/Dense:1, from /home/baiyang/src/fcl/include/fcl/common/types.h:46, from /home/baiyang/src/fcl/include/fcl/math/bv/AABB.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/collision_geometry.h:43, from /home/baiyang/src/fcl/include/fcl/geometry/shape/shape_base.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/shape/box.h:41, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h:47, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h:41, from /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:42: /usr/include/eigen3/Eigen/src/Core/DenseBase.h: In instantiation of ‘class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >’: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:48:34: required from ‘class Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >’ /usr/include/eigen3/Eigen/src/Core/Product.h:151:7: required from ‘class Eigen::internal::dense_product_base<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, 3>’ /usr/include/eigen3/Eigen/src/Core/Product.h:183:7: required from ‘class Eigen::ProductImpl<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, Eigen::Dense>’ /usr/include/eigen3/Eigen/src/Core/Product.h:107:7: required from ‘class Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0>’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:94:33: required from ‘Eigen::RotationBase<Derived, _Dim>::VectorType Eigen::RotationBase<Derived, _Dim>::_transformVector(const OtherVectorType&) const [with OtherVectorType = Eigen::Matrix<float, 3, 1>; Derived = Eigen::AngleAxis; int _Dim = 3; Eigen::RotationBase<Derived, _Dim>::VectorType = Eigen::Matrix<double, 3, 1>; typename Eigen::internal::traits::Scalar = double]’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:128:32: required from ‘static Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::ReturnType Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::run(const RotationDerived&, const OtherVectorType&) [with RotationDerived = Eigen::AngleAxis; OtherVectorType = Eigen::Matrix<float, 3, 1>; Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::ReturnType = Eigen::Matrix<double, 3, 1>; typename RotationDerived::Scalar = double]’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:72:89: required from ‘typename Eigen::internal::rotation_base_generic_product_selector<Derived, OtherDerived, OtherDerived:: IsVectorAtCompileTime>::ReturnType Eigen::RotationBase<Derived, _Dim>::operator*(const Eigen::EigenBase&) const [with OtherDerived = Eigen::Matrix<float, 3, 1>; Derived = Eigen::AngleAxis; int _Dim = 3; typename Eigen::internal::rotation_base_generic_product_selector<Derived, OtherDerived, OtherDerived:: IsVectorAtCompileTime>::ReturnType = Eigen::Matrix<double, 3, 1>]’ /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:242:40: required from here /usr/include/eigen3/Eigen/src/Core/DenseBase.h:78:25: error: using-declaration for non-member at class scope using Base::operator*; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:79:25: error: using-declaration for non-member at class scope using Base::operator/; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:80:17: error: using-declaration for non-member at class scope using Base::derived; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:81:17: error: using-declaration for non-member at class scope using Base::const_cast_derived; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:82:17: error: using-declaration for non-member at class scope using Base::rows; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:83:17: error: using-declaration for non-member at class scope using Base::cols; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:84:17: error: using-declaration for non-member at class scope using Base::size; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:85:17: error: using-declaration for non-member at class scope using Base::rowIndexByOuterInner; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:86:17: error: using-declaration for non-member at class scope using Base::colIndexByOuterInner; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:87:17: error: using-declaration for non-member at class scope using Base::coeff; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:88:17: error: using-declaration for non-member at class scope using Base::coeffByOuterInner; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:89:26: error: using-declaration for non-member at class scope using Base::operator(); ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:90:26: error: using-declaration for non-member at class scope using Base::operator[]; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:91:17: error: using-declaration for non-member at class scope using Base::x; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:92:17: error: using-declaration for non-member at class scope using Base::y; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:93:17: error: using-declaration for non-member at class scope using Base::z; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:94:17: error: using-declaration for non-member at class scope using Base::w; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:95:17: error: using-declaration for non-member at class scope using Base::stride; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:96:17: error: using-declaration for non-member at class scope using Base::innerStride; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:97:17: error: using-declaration for non-member at class scope using Base::outerStride; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:98:17: error: using-declaration for non-member at class scope using Base::rowStride; ^ /usr/include/eigen3/Eigen/src/Core/DenseBase.h:99:17: error: using-declaration for non-member at class scope using Base::colStride; ^ In file included from /usr/include/eigen3/Eigen/Core:345:0, from /usr/include/eigen3/Eigen/Dense:1, from /home/baiyang/src/fcl/include/fcl/common/types.h:46, from /home/baiyang/src/fcl/include/fcl/math/bv/AABB.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/collision_geometry.h:43, from /home/baiyang/src/fcl/include/fcl/geometry/shape/shape_base.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/shape/box.h:41, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h:47, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h:41, from /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:42: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h: In instantiation of ‘class Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >’: /usr/include/eigen3/Eigen/src/Core/Product.h:151:7: required from ‘class Eigen::internal::dense_product_base<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, 3>’ /usr/include/eigen3/Eigen/src/Core/Product.h:183:7: required from ‘class Eigen::ProductImpl<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, Eigen::Dense>’ /usr/include/eigen3/Eigen/src/Core/Product.h:107:7: required from ‘class Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0>’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:94:33: required from ‘Eigen::RotationBase<Derived, _Dim>::VectorType Eigen::RotationBase<Derived, _Dim>::_transformVector(const OtherVectorType&) const [with OtherVectorType = Eigen::Matrix<float, 3, 1>; Derived = Eigen::AngleAxis; int _Dim = 3; Eigen::RotationBase<Derived, _Dim>::VectorType = Eigen::Matrix<double, 3, 1>; typename Eigen::internal::traits::Scalar = double]’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:128:32: required from ‘static Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::ReturnType Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::run(const RotationDerived&, const OtherVectorType&) [with RotationDerived = Eigen::AngleAxis; OtherVectorType = Eigen::Matrix<float, 3, 1>; Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::ReturnType = Eigen::Matrix<double, 3, 1>; typename RotationDerived::Scalar = double]’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:72:89: required from ‘typename Eigen::internal::rotation_base_generic_product_selector<Derived, OtherDerived, OtherDerived:: IsVectorAtCompileTime>::ReturnType Eigen::RotationBase<Derived, _Dim>::operator*(const Eigen::EigenBase&) const [with OtherDerived = Eigen::Matrix<float, 3, 1>; Derived = Eigen::AngleAxis; int _Dim = 3; typename Eigen::internal::rotation_base_generic_product_selector<Derived, OtherDerived, OtherDerived:: IsVectorAtCompileTime>::ReturnType = Eigen::Matrix<double, 3, 1>]’ /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:242:40: required from here /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:70:17: error: no members matching ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}::derived’ in ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}’ using Base::derived; ^ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:71:17: error: no members matching ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}::const_cast_derived’ in ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}’ using Base::const_cast_derived; ^ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:72:17: error: no members matching ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}::rows’ in ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}’ using Base::rows; ^ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:73:17: error: no members matching ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}::cols’ in ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}’ using Base::cols; ^ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:74:17: error: no members matching ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}::size’ in ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}’ using Base::size; ^ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:75:17: error: no members matching ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}::coeff’ in ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}’ using Base::coeff; ^ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:76:17: error: no members matching ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}::coeffRef’ in ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}’ using Base::coeffRef; ^ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:78:17: error: no members matching ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}::eval’ in ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}’ using Base::eval; ^ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:81:25: error: no members matching ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}::operator*=’ in ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}’ using Base::operator*=; ^ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:82:25: error: no members matching ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}::operator/=’ in ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}’ using Base::operator/=; ^ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:83:25: error: no members matching ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}::operator*’ in ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}’ using Base::operator*; ^ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:84:25: error: no members matching ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}::operator/’ in ‘Eigen::MatrixBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >::Base {aka class Eigen::DenseBase<Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0> >}’ using Base::operator/; ^ In file included from /usr/include/eigen3/Eigen/Core:348:0, from /usr/include/eigen3/Eigen/Dense:1, from /home/baiyang/src/fcl/include/fcl/common/types.h:46, from /home/baiyang/src/fcl/include/fcl/math/bv/AABB.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/collision_geometry.h:43, from /home/baiyang/src/fcl/include/fcl/geometry/shape/shape_base.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/shape/box.h:41, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h:47, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h:41, from /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:42: /usr/include/eigen3/Eigen/src/Core/Product.h: In instantiation of ‘class Eigen::ProductImpl<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, Eigen::Dense>’: /usr/include/eigen3/Eigen/src/Core/Product.h:107:7: required from ‘class Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0>’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:94:33: required from ‘Eigen::RotationBase<Derived, _Dim>::VectorType Eigen::RotationBase<Derived, _Dim>::_transformVector(const OtherVectorType&) const [with OtherVectorType = Eigen::Matrix<float, 3, 1>; Derived = Eigen::AngleAxis; int _Dim = 3; Eigen::RotationBase<Derived, _Dim>::VectorType = Eigen::Matrix<double, 3, 1>; typename Eigen::internal::traits::Scalar = double]’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:128:32: required from ‘static Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::ReturnType Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::run(const RotationDerived&, const OtherVectorType&) [with RotationDerived = Eigen::AngleAxis; OtherVectorType = Eigen::Matrix<float, 3, 1>; Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::ReturnType = Eigen::Matrix<double, 3, 1>; typename RotationDerived::Scalar = double]’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:72:89: required from ‘typename Eigen::internal::rotation_base_generic_product_selector<Derived, OtherDerived, OtherDerived:: IsVectorAtCompileTime>::ReturnType Eigen::RotationBase<Derived, _Dim>::operator*(const Eigen::EigenBase&) const [with OtherDerived = Eigen::Matrix<float, 3, 1>; Derived = Eigen::AngleAxis; int _Dim = 3; typename Eigen::internal::rotation_base_generic_product_selector<Derived, OtherDerived, OtherDerived:: IsVectorAtCompileTime>::ReturnType = Eigen::Matrix<double, 3, 1>]’ /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:242:40: required from here /usr/include/eigen3/Eigen/src/Core/Product.h:191:776: error: no members matching ‘Eigen::ProductImpl<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, Eigen::Dense>::Base {aka Eigen::internal::dense_product_base<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, 3>}::derived’ in ‘Eigen::ProductImpl<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, Eigen::Dense>::Base {aka class Eigen::internal::dense_product_base<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, 3>}’ /usr/include/eigen3/Eigen/src/Core/Product.h:191:797: error: no members matching ‘Eigen::ProductImpl<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, Eigen::Dense>::Base {aka Eigen::internal::dense_product_base<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, 3>}::const_cast_derived’ in ‘Eigen::ProductImpl<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, Eigen::Dense>::Base {aka class Eigen::internal::dense_product_base<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, 3>}’ In file included from /usr/include/eigen3/Eigen/Core:348:0, from /usr/include/eigen3/Eigen/Dense:1, from /home/baiyang/src/fcl/include/fcl/common/types.h:46, from /home/baiyang/src/fcl/include/fcl/math/bv/AABB.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/collision_geometry.h:43, from /home/baiyang/src/fcl/include/fcl/geometry/shape/shape_base.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/shape/box.h:41, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h:47, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h:41, from /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:42: /usr/include/eigen3/Eigen/src/Core/Product.h: In instantiation of ‘class Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0>’: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:94:33: required from ‘Eigen::RotationBase<Derived, _Dim>::VectorType Eigen::RotationBase<Derived, _Dim>::_transformVector(const OtherVectorType&) const [with OtherVectorType = Eigen::Matrix<float, 3, 1>; Derived = Eigen::AngleAxis; int _Dim = 3; Eigen::RotationBase<Derived, _Dim>::VectorType = Eigen::Matrix<double, 3, 1>; typename Eigen::internal::traits::Scalar = double]’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:128:32: required from ‘static Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::ReturnType Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::run(const RotationDerived&, const OtherVectorType&) [with RotationDerived = Eigen::AngleAxis; OtherVectorType = Eigen::Matrix<float, 3, 1>; Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::ReturnType = Eigen::Matrix<double, 3, 1>; typename RotationDerived::Scalar = double]’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:72:89: required from ‘typename Eigen::internal::rotation_base_generic_product_selector<Derived, OtherDerived, OtherDerived:: IsVectorAtCompileTime>::ReturnType Eigen::RotationBase<Derived, _Dim>::operator*(const Eigen::EigenBase&) const [with OtherDerived = Eigen::Matrix<float, 3, 1>; Derived = Eigen::AngleAxis; int _Dim = 3; typename Eigen::internal::rotation_base_generic_product_selector<Derived, OtherDerived, OtherDerived:: IsVectorAtCompileTime>::ReturnType = Eigen::Matrix<double, 3, 1>]’ /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:242:40: required from here /usr/include/eigen3/Eigen/src/Core/Product.h:122:776: error: no members matching ‘Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0>::Base {aka Eigen::internal::dense_product_base<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, 3>}::derived’ in ‘Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0>::Base {aka class Eigen::internal::dense_product_base<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, 3>}’ /usr/include/eigen3/Eigen/src/Core/Product.h:122:797: error: no members matching ‘Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0>::Base {aka Eigen::internal::dense_product_base<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, 3>}::const_cast_derived’ in ‘Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0>::Base {aka class Eigen::internal::dense_product_base<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0, 3>}’ In file included from /usr/include/eigen3/Eigen/Geometry:40:0, from /usr/include/eigen3/Eigen/Dense:6, from /home/baiyang/src/fcl/include/fcl/common/types.h:46, from /home/baiyang/src/fcl/include/fcl/math/bv/AABB.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/collision_geometry.h:43, from /home/baiyang/src/fcl/include/fcl/geometry/shape/shape_base.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/shape/box.h:41, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h:47, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h:41, from /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:42: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h: In instantiation of ‘Eigen::RotationBase<Derived, _Dim>::VectorType Eigen::RotationBase<Derived, _Dim>::_transformVector(const OtherVectorType&) const [with OtherVectorType = Eigen::Matrix<float, 3, 1>; Derived = Eigen::AngleAxis; int _Dim = 3; Eigen::RotationBase<Derived, _Dim>::VectorType = Eigen::Matrix<double, 3, 1>; typename Eigen::internal::traits::Scalar = double]’: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:128:32: required from ‘static Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::ReturnType Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::run(const RotationDerived&, const OtherVectorType&) [with RotationDerived = Eigen::AngleAxis; OtherVectorType = Eigen::Matrix<float, 3, 1>; Eigen::internal::rotation_base_generic_product_selector<RotationDerived, OtherVectorType, true>::ReturnType = Eigen::Matrix<double, 3, 1>; typename RotationDerived::Scalar = double]’ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:72:89: required from ‘typename Eigen::internal::rotation_base_generic_product_selector<Derived, OtherDerived, OtherDerived:: IsVectorAtCompileTime>::ReturnType Eigen::RotationBase<Derived, _Dim>::operator*(const Eigen::EigenBase&) const [with OtherDerived = Eigen::Matrix<float, 3, 1>; Derived = Eigen::AngleAxis; int _Dim = 3; typename Eigen::internal::rotation_base_generic_product_selector<Derived, OtherDerived, OtherDerived:: IsVectorAtCompileTime>::ReturnType = Eigen::Matrix<double, 3, 1>]’ /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:242:40: required from here /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h:94:35: error: could not convert ‘((Eigen::MatrixBase<Eigen::Matrix<double, 3, 3> >)(& Eigen::RotationBase<Derived, _Dim>::toRotationMatrix() const with Derived = Eigen::AngleAxis; int _Dim = 3; Eigen::RotationBase<Derived, _Dim>::RotationMatrixType = Eigen::Matrix<double, 3, 3>; typename Eigen::internal::traits::Scalar = double))->Eigen::MatrixBase::operator<Eigen::Matrix<float, 3, 1> >(((const Eigen::MatrixBase<Eigen::Matrix<float, 3, 1> >)(& v)))’ from ‘const Eigen::Product<Eigen::Matrix<double, 3, 3>, Eigen::Matrix<float, 3, 1>, 0>’ to ‘Eigen::RotationBase<Eigen::AngleAxis, 3>::VectorType {aka Eigen::Matrix<double, 3, 1>}’ { return toRotationMatrix() * v; } ^ In file included from /usr/include/eigen3/Eigen/Core:350:0, from /usr/include/eigen3/Eigen/Dense:1, from /home/baiyang/src/fcl/include/fcl/common/types.h:46, from /home/baiyang/src/fcl/include/fcl/math/bv/AABB.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/collision_geometry.h:43, from /home/baiyang/src/fcl/include/fcl/geometry/shape/shape_base.h:41, from /home/baiyang/src/fcl/include/fcl/geometry/shape/box.h:41, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h:47, from /home/baiyang/src/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h:41, from /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:42: /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h: In instantiation of ‘void Eigen::internal::call_assignment_no_alias(Dst&, const Src&, const Func&) [with Dst = Eigen::Matrix<float, 3, 1>; Src = Eigen::Matrix<double, 3, 1>; Func = Eigen::internal::assign_op]’: /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:712:27: required from ‘void Eigen::internal::call_assignment(Dst&, const Src&, const Func&, typename Eigen::internal::enable_if<(! Eigen::internal::evaluator_assume_aliasing::value), void*>::type) [with Dst = Eigen::Matrix<float, 3, 1>; Src = Eigen::Matrix<double, 3, 1>; Func = Eigen::internal::assign_op; typename Eigen::internal::enable_if<(! Eigen::internal::evaluator_assume_aliasing::value), void*>::type = void*]’ /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:693:18: required from ‘void Eigen::internal::call_assignment(Dst&, const Src&) [with Dst = Eigen::Matrix<float, 3, 1>; Src = Eigen::Matrix<double, 3, 1>]’ /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h:682:32: required from ‘Derived& Eigen::PlainObjectBase::_set(const Eigen::DenseBase&) [with OtherDerived = Eigen::Matrix<double, 3, 1>; Derived = Eigen::Matrix<float, 3, 1>]’ /usr/include/eigen3/Eigen/src/Core/Matrix.h:225:24: required from ‘Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>& Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::operator=(const Eigen::DenseBase&) [with OtherDerived = Eigen::Matrix<double, 3, 1>; _Scalar = float; int _Rows = 3; int _Cols = 1; int _Options = 0; int _MaxRows = 3; int _MaxCols = 1]’ /home/baiyang/src/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp:242:17: required from here /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:745:3: error: static assertion failed: YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY EIGEN_CHECK_BINARY_COMPATIBILIY(Func,typename ActualDstTypeCleaned::Scalar,typename Src::Scalar); ^ test/narrowphase/detail/convexity_based_algorithm/CMakeFiles/test_gjk_libccd-inl_epa.dir/build.make:62: recipe for target 'test/narrowphase/detail/convexity_based_algorithm/CMakeFiles/test_gjk_libccd-inl_epa.dir/test_gjk_libccd-inl_epa.cpp.o' failed make[2]: *** [test/narrowphase/detail/convexity_based_algorithm/CMakeFiles/test_gjk_libccd-inl_epa.dir/test_gjk_libccd-inl_epa.cpp.o] Error 1 CMakeFiles/Makefile2:1701: recipe for target 'test/narrowphase/detail/convexity_based_algorithm/CMakeFiles/test_gjk_libccd-inl_epa.dir/all' failed make[1]: *** [test/narrowphase/detail/convexity_based_algorithm/CMakeFiles/test_gjk_libccd-inl_epa.dir/all] Error 2 Makefile:138: recipe for target 'all' failed make: *** [all] Error 2

It occured disarmed after I arm throttle

When I type this command below:

mode guided
arm throttle
takeoff 2

I got the problem below.

STABILIZE> Mode STABILIZE
arm throttle
STABILIZE> APM: Arming motors
Got MAVLink msg: COMMAND_ACK {command : 400, result : 0}
ARMED
takeoff 2
STABILIZE> Take Off started
Got MAVLink msg: COMMAND_ACK {command : 22, result : 4}
takeoffAPM: Disarming motors

Description missing all the requirements & Segmentation fault

I'm trying to use OctomapPlanner following manual.
This repository does not include how, what to install exact requirements to build this repo enough yet.
Missing packages are OpenCV, PCL so far.

OpenCV can be installed with
sudo apt-get install ros-kinetic-opencv3

PCL can be installed with
sudo apt-get install ros-kinetic-pcl-ros

And there's another problem here
launching main node keeps me segfault after RRT* Algorithm fails.

/home/jmarple/OctomapPlanner/src/arduplanner.cpp executePlan: Line 220: No new plan available, waiting for 1 seconds before next callback
/home/jmarple/OctomapPlanner/src/arduplanner.cpp initializeManeuver: Line 294: Desired Yaw: 4.81467
/home/jmarple/OctomapPlanner/src/arduplanner.cpp initializeManeuver: Line 294: Desired Yaw: 4.88444
/home/jmarple/OctomapPlanner/src/arduplanner.cpp initializeManeuver: Line 294: Desired Yaw: 4.95422
/home/jmarple/OctomapPlanner/src/arduplanner.cpp initializeManeuver: Line 294: Desired Yaw: 5.024
/home/jmarple/OctomapPlanner/src/arduplanner.cpp initializeManeuver: Line 294: Desired Yaw: 5.09378
/home/jmarple/OctomapPlanner/src/arduplanner.cpp replanCb: Line 229: Replanner called
/home/jmarple/OctomapPlanner/src/arduplanner.cpp executePlan: Line 220: No new plan available, waiting for 1 seconds before next callback
/home/jmarple/OctomapPlanner/src/Planner.cpp setGoal: Line 139: Goal state: 5 1 1 invalid
/home/jmarple/OctomapPlanner/src/Planner.cpp setStart: Line 112: Start point set to: 2.21468 2.24673 -0.149314
/home/jmarple/OctomapPlanner/src/Planner.cpp replan: Line 180: Replanning
Warning: InformedRRTstar: Skipping invalid start state (invalid bounds)
         at line 253 in /tmp/binarydeb/ros-kinetic-ompl-1.2.3/src/ompl/base/src/Planner.cpp
Debug:   InformedRRTstar: Discarded start state RealVectorState [2.21468 2.24673 -0.149314]

Error:   InformedRRTstar: There are no valid initial states!
         at line 200 in /tmp/binarydeb/ros-kinetic-ompl-1.2.3/src/ompl/geometric/planners/rrt/src/RRTstar.cpp
/home/jmarple/OctomapPlanner/src/Planner.cpp plan: Line 216: No solution found
/home/jmarple/OctomapPlanner/src/arduplanner.cpp replanCb: Line 246: New plan generated
Segmentation fault (core dumped)

Great works though.
Please keep up the work.

Error while compiling "fcl"#2

Thanks for having a look at my problem.
Error:
Scanning dependencies of target test_gjk_libccd-inl_gjk_doSimplex2
[ 95%] Building CXX object test/narrowphase/detail/convexity_based_algorithm/CMakeFiles/test_gjk_libccd-inl_gjk_doSimplex2.dir/test_gjk_libccd-inl_gjk_doSimplex2.cpp.o
/home/user/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_doSimplex2.cpp: In lambda function:
/home/user/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_doSimplex2.cpp:181:67: error: no matching function for call to ‘max()’
const ccd_real_t eps = std::max({1., p_OA.norm(), p_OB.norm()}) * kEps;
^
In file included from /usr/include/c++/5/memory:62:0,
from /home/user/fcl/include/fcl/geometry/collision_geometry.h:41,
from /home/user/fcl/include/fcl/geometry/shape/shape_base.h:41,
from /home/user/fcl/include/fcl/geometry/shape/box.h:41,
from /home/user/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h:47,
from /home/user/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h:41,
from /home/user/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_doSimplex2.cpp:37:
/usr/include/c++/5/bits/stl_algobase.h:219:5: note: candidate: template const _Tp& std::max(const _Tp&, const _Tp&)
max(const _Tp& __a, const _Tp& __b)
^
/usr/include/c++/5/bits/stl_algobase.h:219:5: note: template argument deduction/substitution failed:
/home/user/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_doSimplex2.cpp:181:67: note: candidate expects 2 arguments, 1 provided
const ccd_real_t eps = std::max({1., p_OA.norm(), p_OB.norm()}) * kEps;
^
In file included from /usr/include/c++/5/memory:62:0,
from /home/user/fcl/include/fcl/geometry/collision_geometry.h:41,
from /home/user/fcl/include/fcl/geometry/shape/shape_base.h:41,
from /home/user/fcl/include/fcl/geometry/shape/box.h:41,
from /home/user/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h:47,
from /home/user/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h:41,
from /home/user/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_doSimplex2.cpp:37:
/usr/include/c++/5/bits/stl_algobase.h:265:5: note: candidate: template<class _Tp, class _Compare> const _Tp& std::max(const _Tp&, const _Tp&, _Compare)
max(const _Tp& __a, const _Tp& __b, _Compare __comp)
^
/usr/include/c++/5/bits/stl_algobase.h:265:5: note: template argument deduction/substitution failed:
/home/user/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_doSimplex2.cpp:181:67: note: candidate expects 3 arguments, 1 provided
const ccd_real_t eps = std::max({1., p_OA.norm(), p_OB.norm()}) * kEps;
^
In file included from /usr/include/c++/5/algorithm:62:0,
from /usr/include/eigen3/Eigen/Core:232,
from /usr/include/eigen3/Eigen/Dense:1,
from /home/user/fcl/include/fcl/common/types.h:46,
from /home/user/fcl/include/fcl/math/bv/AABB.h:41,
from /home/user/fcl/include/fcl/geometry/collision_geometry.h:43,
from /home/user/fcl/include/fcl/geometry/shape/shape_base.h:41,
from /home/user/fcl/include/fcl/geometry/shape/box.h:41,
from /home/user/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h:47,
from /home/user/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h:41,
from /home/user/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_doSimplex2.cpp:37:
/usr/include/c++/5/bits/stl_algo.h:3457:5: note: candidate: template _Tp std::max(std::initializer_list<_Tp>)
max(initializer_list<_Tp> __l)
^
/usr/include/c++/5/bits/stl_algo.h:3457:5: note: template argument deduction/substitution failed:
/home/user/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_doSimplex2.cpp:181:67: note: deduced conflicting types for parameter ‘_Tp’ (‘double’ and ‘float’)
const ccd_real_t eps = std::max({1., p_OA.norm(), p_OB.norm()}) * kEps;
^
In file included from /usr/include/c++/5/algorithm:62:0,
from /usr/include/eigen3/Eigen/Core:232,
from /usr/include/eigen3/Eigen/Dense:1,
from /home/user/fcl/include/fcl/common/types.h:46,
from /home/user/fcl/include/fcl/math/bv/AABB.h:41,
from /home/user/fcl/include/fcl/geometry/collision_geometry.h:43,
from /home/user/fcl/include/fcl/geometry/shape/shape_base.h:41,
from /home/user/fcl/include/fcl/geometry/shape/box.h:41,
from /home/user/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h:47,
from /home/user/fcl/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h:41,
from /home/user/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_doSimplex2.cpp:37:
/usr/include/c++/5/bits/stl_algo.h:3463:5: note: candidate: template<class _Tp, class _Compare> _Tp std::max(std::initializer_list<_Tp>, _Compare)
max(initializer_list<_Tp> __l, _Compare __comp)
^
/usr/include/c++/5/bits/stl_algo.h:3463:5: note: template argument deduction/substitution failed:
/home/user/fcl/test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_gjk_doSimplex2.cpp:181:67: note: deduced conflicting types for parameter ‘_Tp’ (‘double’ and ‘float’)
const ccd_real_t eps = std::max({1., p_OA.norm(), p_OB.norm()}) * kEps;
^
test/narrowphase/detail/convexity_based_algorithm/CMakeFiles/test_gjk_libccd-inl_gjk_doSimplex2.dir/build.make:62: recipe for target 'test/narrowphase/detail/convexity_based_algorithm/CMakeFiles/test_gjk_libccd-inl_gjk_doSimplex2.dir/test_gjk_libccd-inl_gjk_doSimplex2.cpp.o' failed
make[2]: *** [test/narrowphase/detail/convexity_based_algorithm/CMakeFiles/test_gjk_libccd-inl_gjk_doSimplex2.dir/test_gjk_libccd-inl_gjk_doSimplex2.cpp.o] Error 1
CMakeFiles/Makefile2:2574: recipe for target 'test/narrowphase/detail/convexity_based_algorithm/CMakeFiles/test_gjk_libccd-inl_gjk_doSimplex2.dir/all' failed
make[1]: *** [test/narrowphase/detail/convexity_based_algorithm/CMakeFiles/test_gjk_libccd-inl_gjk_doSimplex2.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.