Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Compiler options #413

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

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
65 changes: 46 additions & 19 deletions orocos_kdl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@ MESSAGE( STATUS "Orocos KDL version ${VERSION} (${KDL_VERSION_MAJOR}.${KDL_VERSI
SET( PROJ_SOURCE_DIR ${orocos_kdl_SOURCE_DIR} )
SET( PROJ_BINARY_DIR ${orocos_kdl_BINARY_DIR} )

include(GNUInstallDirs)

# catkin-specific configuration (optional)
find_package(catkin QUIET)
if(catkin_FOUND)
Expand All @@ -47,20 +49,23 @@ ELSE ( NOT CMAKE_BUILD_TYPE )
MESSAGE( STATUS "Build type set to '${CMAKE_BUILD_TYPE}' by user." )
ENDIF ( NOT CMAKE_BUILD_TYPE )

SET( KDL_CFLAGS "")
if(MSVC)
add_compile_options(/W4 /WX)
else(MSVC)
add_compile_options(-Wall -Werror=all -Wextra -Werror=extra)
endif(MSVC)

find_package(Eigen3 QUIET)
if(NOT EIGEN3_FOUND)
include(${PROJ_SOURCE_DIR}/cmake/FindEigen3.cmake)
endif()
include_directories(${EIGEN3_INCLUDE_DIR})
include_directories(SYSTEM ${EIGEN3_INCLUDE_DIR})
SET(KDL_CFLAGS "${KDL_CFLAGS} -I\"${EIGEN3_INCLUDE_DIR}\"")

# Check the platform STL containers capabilities
include(cmake/CheckSTLContainers.cmake)
CHECK_STL_CONTAINERS()

# Set the default option appropriately
# Set the default option accordingly
if(HAVE_STL_CONTAINER_INCOMPLETE_TYPES)
set(KDL_USE_NEW_TREE_INTERFACE_DEFAULT OFF)
else(HAVE_STL_CONTAINER_INCOMPLETE_TYPES)
Expand All @@ -80,7 +85,7 @@ endif()
if(KDL_USE_NEW_TREE_INTERFACE)
# We need shared_ptr from boost since not all compilers are c++11 capable
find_package(Boost REQUIRED)
include_directories(${Boost_INCLUDE_DIRS})
include_directories(SYSTEM ${Boost_INCLUDE_DIRS})
endif(KDL_USE_NEW_TREE_INTERFACE)

OPTION(ENABLE_TESTS OFF "Enable building of tests")
Expand Down Expand Up @@ -112,20 +117,42 @@ export(TARGETS orocos-kdl

export(PACKAGE orocos_kdl)

include(CMakePackageConfigHelpers)
# Generate CMake package configuration
CONFIGURE_FILE(orocos_kdl-config.cmake.in
${PROJECT_BINARY_DIR}/orocos_kdl-config.cmake @ONLY)
CONFIGURE_FILE(orocos_kdl-config-version.cmake.in
${PROJECT_BINARY_DIR}/orocos_kdl-config-version.cmake @ONLY)

INSTALL(FILES cmake/FindEigen3.cmake DESTINATION share/orocos_kdl/cmake)
INSTALL(FILES ${PROJECT_BINARY_DIR}/orocos_kdl-config.cmake DESTINATION share/orocos_kdl/cmake)
INSTALL(FILES ${PROJECT_BINARY_DIR}/orocos_kdl-config-version.cmake DESTINATION share/orocos_kdl/cmake)
INSTALL(EXPORT OrocosKDLTargets DESTINATION share/orocos_kdl/cmake)
configure_package_config_file(${CMAKE_CURRENT_SOURCE_DIR}/orocos_kdl-config.cmake.in
${PROJECT_BINARY_DIR}/orocos_kdl-config.cmake
INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/orocos_kdl
)

write_basic_package_version_file(
${PROJECT_BINARY_DIR}/orocos_kdl-config-version.cmake
VERSION ${KDL_VERSION}
COMPATIBILITY SameMajorVersion
)

install(
FILES
${PROJECT_BINARY_DIR}/orocos_kdl-config.cmake
${PROJECT_BINARY_DIR}/orocos_kdl-config-version.cmake
DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/orocos_kdl
)

INSTALL(FILES cmake/FindEigen3.cmake DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/orocos_kdl)
INSTALL(EXPORT OrocosKDLTargets DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/orocos_kdl)

# Generate pkg-config package configuration
CONFIGURE_FILE(orocos_kdl.pc.in ${CMAKE_CURRENT_BINARY_DIR}/orocos-kdl.pc @ONLY)
CONFIGURE_FILE(orocos_kdl.pc.in ${CMAKE_CURRENT_BINARY_DIR}/orocos_kdl.pc @ONLY)

INSTALL(FILES ${CMAKE_CURRENT_BINARY_DIR}/orocos-kdl.pc DESTINATION lib${LIB_SUFFIX}/pkgconfig)
INSTALL(FILES ${CMAKE_CURRENT_BINARY_DIR}/orocos_kdl.pc DESTINATION lib${LIB_SUFFIX}/pkgconfig)
configure_package_config_file(${CMAKE_CURRENT_SOURCE_DIR}/orocos_kdl.pc.in
${PROJECT_BINARY_DIR}/orocos_kdl.pc
INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/pkgconfig
)
configure_package_config_file(${CMAKE_CURRENT_SOURCE_DIR}/orocos_kdl.pc.in
${PROJECT_BINARY_DIR}/orocos-kdl.pc
INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/pkgconfig
)

install(
FILES
${PROJECT_BINARY_DIR}/orocos_kdl.pc
${PROJECT_BINARY_DIR}/orocos-kdl.pc
DESTINATION ${CMAKE_INSTALL_LIBDIR}/pkgconfig
)
22 changes: 0 additions & 22 deletions orocos_kdl/cmake_uninstall.cmake.in

This file was deleted.

11 changes: 0 additions & 11 deletions orocos_kdl/orocos_kdl-config-version.cmake.in

This file was deleted.

1 change: 0 additions & 1 deletion orocos_kdl/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,6 @@ TARGET_INCLUDE_DIRECTORIES(orocos-kdl PUBLIC
SET_TARGET_PROPERTIES( orocos-kdl PROPERTIES
SOVERSION "${KDL_VERSION_MAJOR}.${KDL_VERSION_MINOR}"
VERSION "${KDL_VERSION}"
COMPILE_FLAGS "${CMAKE_CXX_FLAGS_ADD} ${KDL_CFLAGS}"
PUBLIC_HEADER "${KDL_HPPS};${CMAKE_CURRENT_BINARY_DIR}/config.h"
)

Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/chainfdsolver_recursive_newton_euler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ namespace KDL{
return (error = E_NOERROR);
}

void ChainFdSolver_RNE::RK4Integrator(unsigned int& nj, const double& t, double& dt, KDL::JntArray& q, KDL::JntArray& q_dot,
void ChainFdSolver_RNE::RK4Integrator(unsigned int& nj, const double& /*t*/, double& dt, KDL::JntArray& q, KDL::JntArray& q_dot,
KDL::JntArray& torques, KDL::Wrenches& f_ext, KDL::ChainFdSolver_RNE& fdsolver,
KDL::JntArray& q_dotdot, KDL::JntArray& dq, KDL::JntArray& dq_dot,
KDL::JntArray& q_temp, KDL::JntArray& q_dot_temp)
Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/chainhdsolver_vereshchagin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ int ChainHdSolver_Vereshchagin::CartToJnt(const JntArray &q, const JntArray &q_d
return (error = E_NOERROR);
}

void ChainHdSolver_Vereshchagin::initial_upwards_sweep(const JntArray &q, const JntArray &qdot, const JntArray &qdotdot, const Wrenches& f_ext)
void ChainHdSolver_Vereshchagin::initial_upwards_sweep(const JntArray &q, const JntArray &qdot, const JntArray &/*qdotdot*/, const Wrenches& f_ext)
{
//if (q.rows() != nj || qdot.rows() != nj || qdotdot.rows() != nj || f_ext.size() != ns)
// return -1;
Expand Down
4 changes: 4 additions & 0 deletions orocos_kdl/src/frameacc.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,7 @@ class VectorAcc
Vector dv; //!< acceleration vector
public:
VectorAcc():p(),v(),dv() {}
VectorAcc(const VectorAcc& arg) = default;
explicit VectorAcc(const Vector& _p):p(_p),v(Vector::Zero()),dv(Vector::Zero()) {}
VectorAcc(const Vector& _p,const Vector& _v):p(_p),v(_v),dv(Vector::Zero()) {}
VectorAcc(const Vector& _p,const Vector& _v,const Vector& _dv):
Expand Down Expand Up @@ -114,6 +115,7 @@ class RotationAcc
Vector dw; //!< angular acceration vector
public:
RotationAcc():R(),w() {}
RotationAcc(const RotationAcc& arg) = default;
explicit RotationAcc(const Rotation& _R):R(_R),w(Vector::Zero()){}
RotationAcc(const Rotation& _R,const Vector& _w,const Vector& _dw):
R(_R),w(_w),dw(_dw) {}
Expand Down Expand Up @@ -166,6 +168,7 @@ class FrameAcc
VectorAcc p; //!< Translation, velocity and acceleration of origin.
public:
FrameAcc(){}
FrameAcc(const FrameAcc& arg) = default;
explicit FrameAcc(const Frame& _T):M(_T.M),p(_T.p) {}
FrameAcc(const Frame& _T,const Twist& _t,const Twist& _dt):
M(_T.M,_t.rot,_dt.rot),p(_T.p,_t.vel,_dt.vel) {}
Expand Down Expand Up @@ -205,6 +208,7 @@ class TwistAcc
public:

TwistAcc():vel(),rot() {};
TwistAcc(const TwistAcc& arg) = default;
TwistAcc(const VectorAcc& _vel,const VectorAcc& _rot):vel(_vel),rot(_rot) {};

IMETHOD TwistAcc& operator-=(const TwistAcc& arg);
Expand Down
4 changes: 4 additions & 0 deletions orocos_kdl/src/framevel.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,7 @@ class VectorVel
Vector v; // velocity vector
public:
VectorVel():p(),v(){}
VectorVel(const VectorVel& arg) = default;
VectorVel(const Vector& _p,const Vector& _v):p(_p),v(_v) {}
explicit VectorVel(const Vector& _p):p(_p),v(Vector::Zero()) {}

Expand Down Expand Up @@ -154,6 +155,7 @@ class RotationVel
Vector w; // rotation vector
public:
RotationVel():R(),w() {}
RotationVel(const RotationVel& arg) = default;
explicit RotationVel(const Rotation& _R):R(_R),w(Vector::Zero()){}
RotationVel(const Rotation& _R,const Vector& _w):R(_R),w(_w){}

Expand Down Expand Up @@ -219,6 +221,7 @@ class FrameVel
VectorVel p;
public:
FrameVel(){}
FrameVel(const FrameVel& arg) = default;

explicit FrameVel(const Frame& _T):
M(_T.M),p(_T.p) {}
Expand Down Expand Up @@ -277,6 +280,7 @@ class TwistVel

// = Constructors
TwistVel():vel(),rot() {};
TwistVel(const TwistVel& arg) = default;
TwistVel(const VectorVel& _vel,const VectorVel& _rot):vel(_vel),rot(_rot) {};
TwistVel(const Twist& p,const Twist& v):vel(p.vel, v.vel), rot( p.rot, v.rot) {};
TwistVel(const Twist& p):vel(p.vel), rot( p.rot) {};
Expand Down
6 changes: 2 additions & 4 deletions orocos_kdl/src/jntarray.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,15 +55,13 @@ namespace KDL
data.conservativeResizeLike(Eigen::VectorXd::Zero(newSize));
}

double JntArray::operator()(unsigned int i,unsigned int j)const
double JntArray::operator()(unsigned int i,unsigned int /*j*/)const
{
assert(j==0);
return data(i);
}

double& JntArray::operator()(unsigned int i,unsigned int j)
double& JntArray::operator()(unsigned int i,unsigned int /*j*/)
{
assert(j==0);
return data(i);
}

Expand Down
14 changes: 7 additions & 7 deletions orocos_kdl/src/kinfam_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ std::ostream& operator <<(std::ostream& os, const Joint& joint) {
<<", axis: "<<joint.JointAxis() << ", origin"<<joint.JointOrigin()<<"]";
}

std::istream& operator >>(std::istream& is, Joint& joint) {
std::istream& operator >>(std::istream& is, Joint& /*joint*/) {
return is;
}

Expand All @@ -38,7 +38,7 @@ std::ostream& operator <<(std::ostream& os, const Segment& segment) {
return os;
}

std::istream& operator >>(std::istream& is, Segment& segment) {
std::istream& operator >>(std::istream& is, Segment& /*segment*/) {
return is;
}

Expand All @@ -50,7 +50,7 @@ std::ostream& operator <<(std::ostream& os, const Chain& chain) {
return os;
}

std::istream& operator >>(std::istream& is, Chain& chain) {
std::istream& operator >>(std::istream& is, Chain& /*chain*/) {
return is;
}

Expand All @@ -68,7 +68,7 @@ std::ostream& operator <<(std::ostream& os, SegmentMap::const_iterator root) {
return os << "\n";
}

std::istream& operator >>(std::istream& is, Tree& tree) {
std::istream& operator >>(std::istream& is, Tree& /*tree*/) {
return is;
}

Expand All @@ -80,7 +80,7 @@ std::ostream& operator <<(std::ostream& os, const JntArray& array) {
return os;
}

std::istream& operator >>(std::istream& is, JntArray& array) {
std::istream& operator >>(std::istream& is, JntArray& /*array*/) {
return is;
}

Expand All @@ -95,7 +95,7 @@ std::ostream& operator <<(std::ostream& os, const Jacobian& jac) {
return os;
}

std::istream& operator >>(std::istream& is, Jacobian& jac) {
std::istream& operator >>(std::istream& is, Jacobian& /*jac*/) {
return is;
}
std::ostream& operator <<(std::ostream& os, const JntSpaceInertiaMatrix& jntspaceinertiamatrix) {
Expand All @@ -109,7 +109,7 @@ std::ostream& operator <<(std::ostream& os, const JntSpaceInertiaMatrix& jntspac
return os;
}

std::istream& operator >>(std::istream& is, JntSpaceInertiaMatrix& jntspaceinertiamatrix) {
std::istream& operator >>(std::istream& is, JntSpaceInertiaMatrix& /*jntspaceinertiamatrix*/) {
return is;
}

Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/path_composite.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ void Path_Composite::Add(Path* geom, bool aggregate ) {
gv.insert( gv.end(),std::make_pair(geom,aggregate) );
}

double Path_Composite::LengthToS(double length) {
double Path_Composite::LengthToS(double /*length*/) {
throw Error_MotionPlanning_Not_Applicable();
return 0;
}
Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/path_cyclic_closed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ namespace KDL {
Path_Cyclic_Closed::Path_Cyclic_Closed(Path* _geom,int _times, bool _aggregate):
times(_times),geom(_geom), aggregate(_aggregate) {}

double Path_Cyclic_Closed::LengthToS(double length) {
double Path_Cyclic_Closed::LengthToS(double /*length*/) {
throw Error_MotionPlanning_Not_Applicable();
return 0;
}
Expand Down
6 changes: 3 additions & 3 deletions orocos_kdl/src/path_point.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,15 +55,15 @@ double Path_Point::LengthToS(double length) {
double Path_Point::PathLength(){
return 0;
}
Frame Path_Point::Pos(double s) const {
Frame Path_Point::Pos(double /*s*/) const {
return F_base_start;
}

Twist Path_Point::Vel(double s,double sd) const {
Twist Path_Point::Vel(double /*s*/,double /*sd*/) const {
return Twist::Zero();
}

Twist Path_Point::Acc(double s,double sd,double sdd) const {
Twist Path_Point::Acc(double /*s*/,double /*sd*/,double /*sdd*/) const {
return Twist::Zero();
}

Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/rigidbodyinertia.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace KDL{

const static bool mhi=true;

RigidBodyInertia::RigidBodyInertia(double m_,const Vector& h_,const RotationalInertia& I_,bool mhi):
RigidBodyInertia::RigidBodyInertia(double m_,const Vector& h_,const RotationalInertia& I_,bool /*mhi*/):
m(m_),h(h_),I(I_)
{
}
Expand Down
5 changes: 2 additions & 3 deletions orocos_kdl/src/rotational_interpolation_sa.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,11 +60,11 @@ Rotation RotationalInterpolation_SingleAxis::Pos(double theta) const {
return R_base_start* Rotation::Rot2(rot_start_end,theta);
}

Vector RotationalInterpolation_SingleAxis::Vel(double theta,double thetad) const {
Vector RotationalInterpolation_SingleAxis::Vel(double /*theta*/,double thetad) const {
return R_base_start * ( rot_start_end*thetad );
}

Vector RotationalInterpolation_SingleAxis::Acc(double theta,double thetad,double thetadd) const {
Vector RotationalInterpolation_SingleAxis::Acc(double /*theta*/,double /*thetad*/,double thetadd) const {
return R_base_start * ( rot_start_end* thetadd);
}

Expand All @@ -85,4 +85,3 @@ RotationalInterpolation* RotationalInterpolation_SingleAxis::Clone() const {
}

}

6 changes: 3 additions & 3 deletions orocos_kdl/src/trajectory_stationary.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,13 +35,13 @@ namespace KDL {
virtual double Duration() const {
return duration;
}
virtual Frame Pos(double time) const {
virtual Frame Pos(double /*time*/) const {
return pos;
}
virtual Twist Vel(double time) const {
virtual Twist Vel(double /*time*/) const {
return Twist::Zero();
}
virtual Twist Acc(double time) const {
virtual Twist Acc(double /*time*/) const {
return Twist::Zero();
}
virtual void Write(std::ostream& os) const;
Expand Down
Loading