Skip to content

Commit

Permalink
at least compiles with noble+jazzy
Browse files Browse the repository at this point in the history
  • Loading branch information
alaurenzi committed Jul 29, 2024
1 parent e5dc3d3 commit 80a0c61
Show file tree
Hide file tree
Showing 7 changed files with 29 additions and 35 deletions.
10 changes: 4 additions & 6 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,8 @@ find_package(PCL 1.7 QUIET COMPONENTS common
#search
#io)

find_package(eigen_conversions REQUIRED)
find_package(tf2_eigen REQUIRED)
find_package(tf2_eigen_kdl REQUIRED)
find_package(xbot2_interface REQUIRED)
find_package(PkgConfig REQUIRED)
find_package(matlogger2 REQUIRED)
Expand Down Expand Up @@ -84,7 +85,6 @@ set(OPENSOT_CONSTRAINTS_SOURCES src/constraints/Aggregated.cpp
src/constraints/acceleration/TorqueLimits.cpp
src/constraints/velocity/CartesianPositionConstraint.cpp
src/constraints/velocity/CartesianVelocity.cpp
src/constraints/velocity/CoMVelocity.cpp
src/constraints/velocity/JointLimits.cpp
src/constraints/velocity/JointLimitsInvariance.cpp
src/constraints/velocity/VelocityLimits.cpp
Expand Down Expand Up @@ -194,10 +194,10 @@ ADD_LIBRARY(OpenSoT SHARED

set(PRIVATE_TLL ${PRIVATE_TLL} ${eigen_conversions_LIBRARIES})
if(${OPENSOT_COMPILE_COLLISION})
target_link_libraries(OpenSoT PUBLIC xbot2_interface::collision)
target_link_libraries(OpenSoT PUBLIC xbot2_interface::collision moveit_msgs::moveit_msgs__rosidl_generator_cpp tf2_eigen_kdl::tf2_eigen_kdl)
endif()
if(${PCL_FOUND})
set(PRIVATE_TLL ${PRIVATE_TLL} ${QHULL_LIBRARIES} ${PCL_LIBRARIES})
set(PRIVATE_TLL ${PRIVATE_TLL} ${QHULL_LIBRARIES} ${PCL_LIBRARIES} tf2_eigen::tf2_eigen )
endif()


Expand Down Expand Up @@ -324,8 +324,6 @@ library_install(OpenSoT
${PROJECT_VERSION_PATCH})


add_subdirectory(doc)

include(GenerateDeb)


Expand Down
3 changes: 3 additions & 0 deletions OpenSoTConfig.cmake.in
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,9 @@
include(CMakeFindDependencyMacro)
find_dependency(xbot2_interface)
find_dependency(matlogger2)
find_dependency(moveit_msgs)
find_dependency(tf2_eigen_kdl)
find_dependency(tf2_eigen)

set_and_check(OpenSoT_TARGETS
"${CMAKE_CURRENT_LIST_DIR}/OpenSoTTargets.cmake")
Expand Down
10 changes: 2 additions & 8 deletions bindings/python/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,12 +1,6 @@
cmake_minimum_required(VERSION 3.5)

if(${CMAKE_VERSION} VERSION_LESS "3.12.0")
message("Please consider to switch to latest version to enable
more reliable Python3 binaries detection")
else()
#find_package(Python ${PYBIND11_PYTHON_VERSION} COMPONENTS Development Interpreter REQUIRED)
endif()
cmake_minimum_required(VERSION 3.20)

find_package(Python ${PYBIND11_PYTHON_VERSION} COMPONENTS Development Interpreter REQUIRED)
find_package(pybind11 QUIET)

message(STATUS "check for pybind11")
Expand Down
4 changes: 2 additions & 2 deletions include/OpenSoT/solvers/OSQPBackEnd.h
Original file line number Diff line number Diff line change
Expand Up @@ -141,8 +141,8 @@ class OSQPBackEnd: public BackEnd{

private:

typedef Eigen::SparseMatrix<double> SparseMatrix;
typedef Eigen::SparseMatrix<double, Eigen::RowMajor> SparseMatrixRowMajor;
typedef Eigen::SparseMatrix<double, Eigen::ColMajor, c_int> SparseMatrix;
typedef Eigen::SparseMatrix<double, Eigen::RowMajor, c_int> SparseMatrixRowMajor;

/**
* @brief __generate_data_struct creates DENSE Hessian and Constraints matrices using a SPARSE representation.
Expand Down
2 changes: 1 addition & 1 deletion src/solvers/OSQPBackEnd.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ void OpenSoT::solvers::OSQPBackEnd::update_data_struct()
}


void OSQPBackEnd::setCSCMatrix(csc* a, Eigen::SparseMatrix<double>& A)
void OSQPBackEnd::setCSCMatrix(csc* a, SparseMatrix& A)
{
a->m = A.rows();
a->n = A.cols();
Expand Down
28 changes: 14 additions & 14 deletions src/tasks/acceleration/Cartesian.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include <OpenSoT/tasks/acceleration/Cartesian.h>
#include <xbot2_interface/logger.h>
#include <eigen_conversions/eigen_kdl.h>
#include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>

using XBot::Logger;
using namespace OpenSoT::tasks::acceleration;
Expand Down Expand Up @@ -215,8 +215,8 @@ void Cartesian::setReference(const Eigen::Affine3d& pose_ref,
void Cartesian::setReference(const KDL::Frame& pose_ref,
const KDL::Twist& vel_ref)
{
tf::transformKDLToEigen(pose_ref, _pose_ref);
tf::twistKDLToEigen(vel_ref, _vel_ref);
tf2::transformKDLToEigen(pose_ref, _pose_ref);
tf2::twistKDLToEigen(vel_ref, _vel_ref);
_acc_ref.setZero();

_vel_ref_cached = _vel_ref;
Expand All @@ -239,9 +239,9 @@ void Cartesian::setReference(const KDL::Frame& pose_ref,
const KDL::Twist& vel_ref,
const KDL::Twist& acc_ref)
{
tf::transformKDLToEigen(pose_ref, _pose_ref);
tf::twistKDLToEigen(vel_ref, _vel_ref);
tf::twistKDLToEigen(acc_ref, _acc_ref);
tf2::transformKDLToEigen(pose_ref, _pose_ref);
tf2::twistKDLToEigen(vel_ref, _vel_ref);
tf2::twistKDLToEigen(acc_ref, _acc_ref);

_vel_ref_cached = _vel_ref;
_acc_ref_cached = _acc_ref;
Expand Down Expand Up @@ -319,7 +319,7 @@ void Cartesian::getReference(Eigen::Affine3d& ref) const

void Cartesian::getReference(KDL::Frame& ref) const
{
tf::transformEigenToKDL(_pose_ref, ref);
tf2::transformEigenToKDL(_pose_ref, ref);
}

void Cartesian::getReference(Eigen::Affine3d& desiredPose,
Expand All @@ -332,8 +332,8 @@ void Cartesian::getReference(Eigen::Affine3d& desiredPose,
void Cartesian::getReference(KDL::Frame& desiredPose,
KDL::Twist& desiredTwist) const
{
tf::transformEigenToKDL(_pose_ref, desiredPose);
tf::twistEigenToKDL(_vel_ref, desiredTwist);
tf2::transformEigenToKDL(_pose_ref, desiredPose);
tf2::twistEigenToKDL(_vel_ref, desiredTwist);
}

void Cartesian::getReference(Eigen::Affine3d& desiredPose,
Expand All @@ -349,9 +349,9 @@ void Cartesian::getReference(KDL::Frame& desiredPose,
KDL::Twist& desiredTwist,
KDL::Twist& desiredAcceleration) const
{
tf::transformEigenToKDL(_pose_ref, desiredPose);
tf::twistEigenToKDL(_vel_ref, desiredTwist);
tf::twistEigenToKDL(_acc_ref, desiredAcceleration);
tf2::transformEigenToKDL(_pose_ref, desiredPose);
tf2::twistEigenToKDL(_vel_ref, desiredTwist);
tf2::twistEigenToKDL(_acc_ref, desiredAcceleration);
}


Expand All @@ -362,7 +362,7 @@ void Cartesian::getActualPose(Eigen::Affine3d& actual) const

void Cartesian::getActualPose(KDL::Frame& actual)
{
tf::transformEigenToKDL(_pose_current, actual);
tf2::transformEigenToKDL(_pose_current, actual);
}

const Eigen::Affine3d& Cartesian::getActualPose() const
Expand All @@ -377,7 +377,7 @@ void Cartesian::getActualTwist(Eigen::Vector6d& actual) const

void Cartesian::getActualTwist(KDL::Twist& actual)
{
tf::twistEigenToKDL(_vel_current, actual);
tf2::twistEigenToKDL(_vel_current, actual);
}

const Eigen::Vector6d& Cartesian::getActualTwist() const
Expand Down
7 changes: 3 additions & 4 deletions src/utils/cartesian_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,7 @@

#include <OpenSoT/utils/cartesian_utils.h>
#include <memory>
#include <eigen_conversions/eigen_kdl.h>

#include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
#define toDeg(X) (X*180.0/M_PI)


Expand All @@ -45,14 +44,14 @@ void cartesian_utils::computeCartesianError(const Eigen::Matrix4d &T,
KDL::Frame x; // ee pose
x.Identity();
Eigen::Matrix4d tmp = T;
tf::transformEigenToKDL(Eigen::Affine3d(tmp),x);
tf2::transformEigenToKDL(Eigen::Affine3d(tmp),x);
quaternion q;
x.M.GetQuaternion(q.x, q.y, q.z, q.w);

KDL::Frame xd; // ee desired pose
xd.Identity();
tmp = Td;
tf::transformEigenToKDL(Eigen::Affine3d(tmp),xd);
tf2::transformEigenToKDL(Eigen::Affine3d(tmp),xd);
quaternion qd;
xd.M.GetQuaternion(qd.x, qd.y, qd.z, qd.w);

Expand Down

0 comments on commit 80a0c61

Please sign in to comment.