diff --git a/CMakeLists.txt b/CMakeLists.txt index b5a9f38..82e036d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.10.0) project(libada) -set(library_VERSION 0.2.0) +set(library_VERSION 0.3.0) option(LIBADA_TREAT_WARNINGS_AS_ERRORS "Treat warnings as errors" OFF) @@ -8,6 +8,34 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14") set(CMAKE_CXX_STANDARD 14) list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") +#================================================================================ +# Python setup +# + +set(ADAPY_PYTHON_VERSION 3.8) +find_package(PythonInterp ${ADAPY_PYTHON_VERSION}) + +if(PythonInterp_FOUND) + execute_process(COMMAND ${PYTHON_EXECUTABLE} -c + "from distutils.sysconfig import get_python_lib;\ + print(get_python_lib(plat_specific=True, prefix=''))" + OUTPUT_VARIABLE PYTHON_SITE_PACKAGES + OUTPUT_STRIP_TRAILING_WHITESPACE + ) + + find_package(PythonLibs ${ADAPY_PYTHON_VERSION}) + + # Find pybind11 + # Needs to set PYBIND11_PYTHON_VERSION before finding pybind11 + set(PYBIND11_PYTHON_VERSION ${ADAPY_PYTHON_VERSION} CACHE STRING "") + find_package(pybind11 2.2.0) +endif() + +if(NOT pybind11_FOUND) + message(WARNING "Could not load pybind11. Cannot build python bindings.") + return() +endif() + #================================================================================ # CodeCov setup # @@ -28,7 +56,6 @@ include(ExternalProject) find_package(DART 6.8.5 REQUIRED COMPONENTS utils utils-urdf optimizer-nlopt - ) find_package(aikido 0.3.0 REQUIRED @@ -47,6 +74,7 @@ find_package(aikido 0.3.0 REQUIRED robot statespace io + rviz ) find_package(ada_description REQUIRED) @@ -116,6 +144,33 @@ target_link_libraries(libada ${urdf_LIBRARIES} ) +#============================================================================= +#Pybind +if(pybind11_FOUND) + pybind11_add_module(adapy + MODULE + python/adapy/adapy.cpp + python/adapy/ada_bindings.cpp + python/adapy/aikido_bindings.cpp + python/adapy/dart_bindings.cpp + python/adapy/pr_tsr_bindings.cpp + python/adapy/ik_bindings.cpp + ) + + target_include_directories(adapy + SYSTEM PUBLIC + ${PYTHON_INCLUDE_DIRS} + ${pybind11_INCLUDE_DIRS} + PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR} + ) + + target_link_libraries(adapy PUBLIC + libada + ${DART_LIBRARIES} + ) +endif() + #================================================================================ # Testing # @@ -164,6 +219,10 @@ install(FILES "package.xml" DESTINATION "share/libada") #install(DIRECTORY resources DESTINATION share) +if(pybind11_FOUND) + install(TARGETS adapy + LIBRARY DESTINATION lib/python3/dist-packages) +endif() #================================================================================ @@ -177,7 +236,13 @@ if(CLANG_FORMAT_EXECUTABLE) file(GLOB_RECURSE ALL_SOURCE_FILES LIST_DIRECTORIES false - include/*.h include/*.hpp src/*.c src/*.cpp tests/*.cpp tests/*.hpp) + include/*.h + include/*.hpp + src/*.c + src/*.cpp + tests/*.cpp + tests/*.hpp + python/*.cpp) clang_format_add_sources(${ALL_SOURCE_FILES}) diff --git a/include/libada/Ada.hpp b/include/libada/Ada.hpp index 902925b..55b79cb 100644 --- a/include/libada/Ada.hpp +++ b/include/libada/Ada.hpp @@ -89,7 +89,8 @@ class Ada final : public aikido::robot::Robot const dart::common::Uri& adaUrdfUri = defaultAdaUrdfUri, const dart::common::Uri& adaSrdfUri = defaultAdaSrdfUri, const std::string& endEffectorName = "j2n6s200_end_effector", - const std::string& armTrajectoryExecutorName = "trajectory_controller", + const std::string& armTrajectoryExecutorName + = "rewd_trajectory_controller", const ::ros::NodeHandle* node = nullptr, aikido::common::RNG::result_type rngSeed = std::random_device{}(), const dart::common::ResourceRetrieverPtr& retriever @@ -176,6 +177,29 @@ class Ada final : public aikido::robot::Robot // Runs step with current time. void update(); + /// Generates a timed (but not smoothed) trajectory from the given list of + /// configurations. + /// \param[in] stateSpace The statespace for the trajectory. + /// \param[in] waypoints Ordered configurations to add to the trajectory, each + /// of which is paired with its desired time along the output trajectory. + /// \return Timed trajectory. + aikido::trajectory::TrajectoryPtr computeRetimedJointSpacePath( + const aikido::statespace::dart::MetaSkeletonStateSpacePtr& stateSpace, + const std::vector>& waypoints); + + /// Generates a timed *and* smoothed trajectory from the given list of + /// configurations. + /// \param[in] space The statespace for the trajectory. + /// \param[in] waypoints Ordered configurations to add to the trajectory, each + /// of which is paired with its desired time along the output trajectory. + /// \param[in] collisionFree Collision constraint during post-processing. + /// \return Timed amd smoothed trajectory. + aikido::trajectory::TrajectoryPtr computeSmoothJointSpacePath( + const aikido::statespace::dart::MetaSkeletonStateSpacePtr& stateSpace, + const std::vector>& waypoints, + const aikido::constraint::dart::CollisionFreePtr& collisionFree + = nullptr); + /// \copydoc Robot::planToConfiguration. aikido::trajectory::TrajectoryPtr planToConfiguration( const aikido::statespace::dart::MetaSkeletonStateSpacePtr& stateSpace, diff --git a/include/libada/AdaHand.hpp b/include/libada/AdaHand.hpp index 167acfb..145c56f 100644 --- a/include/libada/AdaHand.hpp +++ b/include/libada/AdaHand.hpp @@ -83,6 +83,10 @@ class AdaHand : public aikido::robot::Hand // Documentation inherited. std::future executePreshape(const std::string& preshapeName) override; + /// Sets the hand to the given preshape configuration. + /// \param[in] preshape Configuration of the hand. + std::future executePreshape(const Eigen::Vector2d& preshape); + // Documentation inherited. void step(const std::chrono::system_clock::time_point& timepoint) override; diff --git a/include/libada/detail/Ada-impl.hpp b/include/libada/detail/Ada-impl.hpp index 22c4cf2..991aaf4 100644 --- a/include/libada/detail/Ada-impl.hpp +++ b/include/libada/detail/Ada-impl.hpp @@ -10,17 +10,23 @@ aikido::trajectory::UniqueSplinePtr Ada::postProcessPath( const Eigen::VectorXd& velocityLimits, const Eigen::VectorXd& accelerationLimits) { + // Don't plan above 70% hard velocity limit + // Unless requested explicitly + const double DEFAULT_LIMITS_BUFFER = 0.7; + bool velLimitsInvalid = (velocityLimits.squaredNorm() == 0.0) || velocityLimits.size() != getVelocityLimits().size(); - auto sentVelocityLimits - = velLimitsInvalid ? getVelocityLimits() : velocityLimits; + auto sentVelocityLimits = velLimitsInvalid + ? DEFAULT_LIMITS_BUFFER * getVelocityLimits() + : velocityLimits; bool accLimitsInvalid = (accelerationLimits.squaredNorm() == 0.0) || accelerationLimits.size() != getAccelerationLimits().size(); auto sentAccelerationLimits - = accLimitsInvalid ? getAccelerationLimits() : accelerationLimits; + = accLimitsInvalid ? DEFAULT_LIMITS_BUFFER * getAccelerationLimits() + : accelerationLimits; return mRobot->postProcessPath( sentVelocityLimits, diff --git a/package.xml b/package.xml index 84c810f..99627b6 100644 --- a/package.xml +++ b/package.xml @@ -14,6 +14,7 @@ roslib srdfdom urdf + roscpp_initializer nlopt diff --git a/python/adapy/ada_bindings.cpp b/python/adapy/ada_bindings.cpp new file mode 100644 index 0000000..0aee723 --- /dev/null +++ b/python/adapy/ada_bindings.cpp @@ -0,0 +1,296 @@ +#include +#include +#include +#include +#include +#include + +#include +#include "libada/Ada.hpp" +#include "aikido/constraint/Satisfied.hpp" +#include "aikido/planner/kunzretimer/KunzRetimer.hpp" +#include "aikido/statespace/ScopedState.hpp" +namespace py = pybind11; + +using aikido::planner::kunzretimer::KunzRetimer; + +//============================================================================== +// NOTE: These functions define the Python API for Ada. + +std::shared_ptr +get_self_collision_constraint(ada::Ada* self) +{ + return self->getSelfCollisionConstraint( + self->getStateSpace(), self->getMetaSkeleton()); +} + +void start_trajectory_executor(ada::Ada* self) +{ + self->startTrajectoryExecutor(); +} + +void stop_trajectory_executor(ada::Ada* self) +{ + self->stopTrajectoryExecutor(); +} + +std::string get_name(ada::Ada* self) +{ + return self->getName(); +} + +aikido::planner::WorldPtr get_world(ada::Ada* self) +{ + return self->getWorld(); +} + +ada::AdaHandPtr get_hand(ada::Ada* self) +{ + return self->getHand(); +} + +dart::dynamics::MetaSkeletonPtr get_skeleton(ada::Ada* self) +{ + return self->getMetaSkeleton(); +} + +dart::dynamics::MetaSkeletonPtr get_arm_skeleton(ada::Ada* self) +{ + return self->getArm()->getMetaSkeleton(); +} + +aikido::statespace::dart::MetaSkeletonStateSpacePtr get_arm_state_space( + ada::Ada* self) +{ + return self->getArm()->getStateSpace(); +} + +void set_positions(ada::Ada* self, const Eigen::VectorXd& configuration) +{ + auto arm = self->getArm(); + auto armSkeleton = arm->getMetaSkeleton(); + armSkeleton->setPositions(configuration); +} + +std::shared_ptr +set_up_collision_detection( + ada::Ada* self, + const aikido::statespace::dart::MetaSkeletonStateSpacePtr& armSpace, + const dart::dynamics::MetaSkeletonPtr& armSkeleton, + const std::vector& envSkeletons) +{ + dart::collision::FCLCollisionDetectorPtr collisionDetector + = dart::collision::FCLCollisionDetector::create(); + std::shared_ptr armCollisionGroup + = collisionDetector->createCollisionGroup(self->getMetaSkeleton().get()); + std::shared_ptr envCollisionGroup + = collisionDetector->createCollisionGroup(); + for (const auto& envSkeleton : envSkeletons) + { + envCollisionGroup->addShapeFramesOf(envSkeleton.get()); + } + std::shared_ptr + collisionFreeConstraint + = std::make_shared( + armSpace, armSkeleton, collisionDetector); + collisionFreeConstraint->addPairwiseCheck( + armCollisionGroup, envCollisionGroup); + return collisionFreeConstraint; +} + +aikido::constraint::TestablePtr get_full_collision_constraint( + ada::Ada* self, + const aikido::statespace::dart::MetaSkeletonStateSpacePtr& armSpace, + const dart::dynamics::MetaSkeletonPtr& armSkeleton, + const aikido::constraint::dart::CollisionFreePtr& collisionFreeConstraint) +{ + return self->getFullCollisionConstraint( + armSpace, armSkeleton, collisionFreeConstraint); +} + +aikido::trajectory::TrajectoryPtr compute_joint_space_path( + ada::Ada* self, + const aikido::statespace::dart::MetaSkeletonStateSpacePtr& stateSpace, + const std::vector>& waypoints) +{ + return self->computeRetimedJointSpacePath(stateSpace, waypoints); +} + +aikido::trajectory::TrajectoryPtr compute_smooth_joint_space_path( + ada::Ada* self, + const aikido::statespace::dart::MetaSkeletonStateSpacePtr& stateSpace, + const std::vector>& waypoints, + const aikido::constraint::dart::CollisionFreePtr& collisionFreeConstraint + = nullptr) +{ + return self->computeSmoothJointSpacePath( + stateSpace, waypoints, collisionFreeConstraint); +} + +aikido::trajectory::TrajectoryPtr compute_retime_path( + ada::Ada* self, + const dart::dynamics::MetaSkeletonPtr& armSkeleton, + aikido::trajectory::InterpolatedPtr trajectory_ptr) +{ + auto satisfied = std::make_shared( + trajectory_ptr->getStateSpace()); + return self->postProcessPath( + trajectory_ptr.get(), + satisfied, + ada::KunzParams(), + armSkeleton->getVelocityUpperLimits(), + armSkeleton->getAccelerationUpperLimits()); +} + +aikido::trajectory::TrajectoryPtr plan_to_configuration( + ada::Ada* self, + const aikido::statespace::dart::MetaSkeletonStateSpacePtr& armSpace, + const dart::dynamics::MetaSkeletonPtr& armSkeleton, + const Eigen::VectorXd& configuration) +{ + auto state = armSpace->createState(); + armSpace->convertPositionsToState(configuration, state); + auto trajectory + = self->planToConfiguration(armSpace, armSkeleton, state, nullptr, 10); + return trajectory; +} + +void execute_trajectory( + ada::Ada* self, const aikido::trajectory::TrajectoryPtr& trajectory) +{ + auto future = self->executeTrajectory(trajectory); + + if (!future.valid()) + { + std::__throw_future_error(0); + } + future.wait(); + // Throw any exceptions + future.get(); +} + +std::shared_ptr start_viewer( + ada::Ada* self, + const std::string& topicName, + const std::string& baseFrameName) +{ + auto viewer = std::make_shared( + topicName, baseFrameName, self->getWorld()); + viewer->setAutoUpdate(true); + return viewer; +} + +//============================================================================== +// NOTE: These functions define the Python API for AdaHand. + +dart::dynamics::MetaSkeletonPtr hand_get_skeleton(ada::AdaHand* self) +{ + return self->getMetaSkeleton(); +} + +aikido::statespace::dart::MetaSkeletonStateSpacePtr hand_get_state_space( + ada::AdaHand* self) +{ + auto handSkeleton = self->getMetaSkeleton(); + auto handSpace + = std::make_shared( + handSkeleton.get()); + return handSpace; +} + +void execute_preshape(ada::AdaHand* self, const Eigen::Vector2d& d) +{ + auto future = self->executePreshape(d); + + if (!future.valid()) + { + std::__throw_future_error(0); + } + + future.wait(); + // Throw any exceptions + future.get(); +} + +void hand_open(ada::AdaHand* self) +{ + auto future = self->executePreshape("open"); + + if (!future.valid()) + { + std::__throw_future_error(0); + } + + future.wait(); + // Throw any exceptions + future.get(); +} + +void hand_close(ada::AdaHand* self) +{ + auto future = self->executePreshape("closed"); + + if (!future.valid()) + { + std::__throw_future_error(0); + } + + future.wait(); + // Throw any exceptions + future.get(); +} + +Eigen::Matrix4d get_endeffector_transform( + ada::AdaHand* self, const std::string& objectType) +{ + return self->getEndEffectorTransform(objectType)->matrix(); +} + +dart::dynamics::BodyNode* get_endeffector_body_node(ada::AdaHand* self) +{ + return self->getEndEffectorBodyNode(); +} + +void grab(ada::AdaHand* self, dart::dynamics::SkeletonPtr object) +{ + self->grab(object); +} + +//====================================LIBADA==================================== + +void Ada(pybind11::module& m) +{ + py::class_>(m, "Ada") + .def(py::init([](bool simulation) -> std::shared_ptr { + return std::make_shared( + aikido::planner::World::create(), simulation); + })) + .def("get_self_collision_constraint", get_self_collision_constraint) + .def("start_trajectory_executor", start_trajectory_executor) + .def("stop_trajectory_executor", stop_trajectory_executor) + .def("get_name", get_name) + .def("get_world", get_world) + .def("get_hand", get_hand) + .def("get_skeleton", get_skeleton) + .def("get_arm_skeleton", get_arm_skeleton) + .def("get_arm_state_space", get_arm_state_space) + .def("set_positions", set_positions) + .def("set_up_collision_detection", set_up_collision_detection) + .def("get_full_collision_constraint", get_full_collision_constraint) + .def("compute_joint_space_path", compute_joint_space_path) + .def("compute_smooth_joint_space_path", compute_smooth_joint_space_path) + .def("compute_retime_path", compute_retime_path) + .def("plan_to_configuration", plan_to_configuration) + .def("execute_trajectory", execute_trajectory) + .def("start_viewer", start_viewer); + + py::class_>(m, "AdaHand") + .def("get_skeleton", hand_get_skeleton) + .def("get_state_space", hand_get_state_space) + .def("execute_preshape", execute_preshape) + .def("open", hand_open) + .def("close", hand_close) + .def("get_endeffector_transform", get_endeffector_transform) + .def("get_endeffector_body_node", get_endeffector_body_node) + .def("grab", grab); +} diff --git a/python/adapy/adapy.cpp b/python/adapy/adapy.cpp new file mode 100644 index 0000000..e2ba7c0 --- /dev/null +++ b/python/adapy/adapy.cpp @@ -0,0 +1,25 @@ +#include +#include +#include +#include + +namespace py = pybind11; + +void Ada(pybind11::module& m); +void Aikido(pybind11::module& m); +void Dart(pybind11::module& m); +void Pr_Tsr(pybind11::module& m); +void IK(pybind11::module& m); + +PYBIND11_MODULE(adapy, m) +{ + Ada(m); + + Aikido(m); + + Dart(m); + + Pr_Tsr(m); + + IK(m); +} diff --git a/python/adapy/aikido_bindings.cpp b/python/adapy/aikido_bindings.cpp new file mode 100644 index 0000000..b9930c0 --- /dev/null +++ b/python/adapy/aikido_bindings.cpp @@ -0,0 +1,174 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "aikido/statespace/ScopedState.hpp" +#include "aikido/statespace/StateHandle.hpp" +#include "aikido/statespace/StateSpace.hpp" + +namespace py = pybind11; + +Eigen::Isometry3d vectorToIsometry(std::vector& poseVector) +{ + double* ptr = &poseVector[0]; + Eigen::Map p(ptr, 7); + + Eigen::Isometry3d pose(Eigen::Isometry3d::Identity()); + pose.translation() = p.head(3); + Eigen::Quaterniond q(p[3], p[4], p[5], p[6]); + pose.linear() = Eigen::Matrix3d(q); + return pose; +} + +Eigen::Isometry3d matrixToIsometry(Eigen::Matrix4d& poseMatrix) +{ + Eigen::Isometry3d pose(Eigen::Isometry3d::Identity()); + pose.translation() = poseMatrix.block<3, 1>(0, 3); + pose.linear() = poseMatrix.block<3, 3>(0, 0); + return pose; +} + +//============================================================================== +// NOTE: These functions define the Python API for World. + +std::shared_ptr<::dart::dynamics::Skeleton> add_body_from_urdf( + aikido::planner::World* self, + const std::string& uri, + std::vector objectPose) +{ + auto transform = vectorToIsometry(objectPose); + + const auto skeleton = aikido::io::loadSkeletonFromURDF( + std::make_shared(), uri); + + if (!skeleton) + throw std::runtime_error("unable to load '" + uri + "'"); + + dynamic_cast(skeleton->getJoint(0)) + ->setTransform(transform); + + self->addSkeleton(skeleton); + return skeleton; +} + +std::shared_ptr<::dart::dynamics::Skeleton> add_body_from_urdf_matrix( + aikido::planner::World* self, + const std::string& uri, + Eigen::Matrix4d& objectPose) +{ + auto transform = matrixToIsometry(objectPose); + + const auto skeleton = aikido::io::loadSkeletonFromURDF( + std::make_shared(), uri); + + if (!skeleton) + throw std::runtime_error("unable to load '" + uri + "'"); + + dynamic_cast(skeleton->getJoint(0)) + ->setTransform(transform); + + self->addSkeleton(skeleton); + return skeleton; +} + +void remove_skeleton( + aikido::planner::World* self, + std::shared_ptr<::dart::dynamics::Skeleton> skeleton) +{ + self->removeSkeleton(skeleton); +} + +dart::dynamics::SkeletonPtr get_skeleton(aikido::planner::World* self, int i) +{ + return self->getSkeleton(i); +} + +//============================================================================== +// NOTE: These functions define the Python API for InteractiveMarkerViewer. + +void update(aikido::rviz::InteractiveMarkerViewer* self) +{ + self->update(); +} + +void add_frame( + aikido::rviz::InteractiveMarkerViewer* self, dart::dynamics::BodyNode* node) +{ + self->addFrameMarker(node); +} + +aikido::rviz::TSRMarkerPtr add_tsr_marker( + aikido::rviz::InteractiveMarkerViewer* self, + std::shared_ptr tsr) +{ + return self->addTSRMarker(*tsr.get()); +} + +//============================================================================== +// NOTE: These functions define the Python API for Testable. + +bool is_satisfied( + aikido::constraint::Testable* self, + const aikido::statespace::dart::MetaSkeletonStateSpacePtr& armSpace, + const dart::dynamics::MetaSkeletonPtr& armSkeleton, + const Eigen::VectorXd& positions) +{ + auto armState = armSpace->createState(); + armSpace->convertPositionsToState(positions, armState); + auto currentState + = armSpace->getScopedStateFromMetaSkeleton(armSkeleton.get()); + aikido::constraint::DefaultTestableOutcome fullCollisionCheckOutcome; + bool collisionResult + = self->isSatisfied(armState, &fullCollisionCheckOutcome); + armSpace->setState(armSkeleton.get(), currentState); + return collisionResult; +} + +//====================================AIKIDO==================================== + +void Aikido(pybind11::module& m) +{ + py::class_>( + m, "World") + .def("add_body_from_urdf", add_body_from_urdf) + .def("add_body_from_urdf_matrix", add_body_from_urdf_matrix) + .def("remove_skeleton", remove_skeleton) + .def("get_skeleton", get_skeleton); + + py::class_< + aikido::rviz::InteractiveMarkerViewer, + std::shared_ptr>( + m, "InteractiveMarkerViewer") + .def("update", update) + .def("add_frame", add_frame) + .def("add_tsr_marker", add_tsr_marker); + + py::class_< + aikido::constraint::dart::CollisionFree, + std::shared_ptr>( + m, "CollisionFree"); + + py::class_< + aikido::statespace::dart::MetaSkeletonStateSpace, + aikido::statespace::dart::MetaSkeletonStateSpacePtr>( + m, "MetaSkeletonStateSpace"); + + py::class_( + m, "Trajectory"); + + py::class_( + m, "TSRMarker"); + + py::class_( + m, "FullCollisionFree") + .def("is_satisfied", is_satisfied); +} diff --git a/python/adapy/dart_bindings.cpp b/python/adapy/dart_bindings.cpp new file mode 100644 index 0000000..f1efc80 --- /dev/null +++ b/python/adapy/dart_bindings.cpp @@ -0,0 +1,79 @@ +#include +#include +#include +#include +#include +#include +#include +#include + +namespace py = pybind11; + +//============================================================================== +// NOTE: These functions define the Python API for Skeleton. + +std::string skeleton_get_name(dart::dynamics::Skeleton* self) +{ + return self->getName(); +} + +Eigen::VectorXd skeleton_get_positions(dart::dynamics::Skeleton* self) +{ + return self->getPositions(); +} + +int skeleton_get_num_joints(dart::dynamics::Skeleton* self) +{ + return self->getNumJoints(); +} + +//============================================================================== +// NOTE: These functions define the Python API for MetaSkeleton. + +std::string metaskeleton_get_name(dart::dynamics::MetaSkeleton* self) +{ + return self->getName(); +} + +Eigen::VectorXd metaskeleton_get_positions(dart::dynamics::MetaSkeleton* self) +{ + return self->getPositions(); +} + +int metaskeleton_get_num_joints(dart::dynamics::MetaSkeleton* self) +{ + return self->getNumJoints(); +} + +dart::math::LinearJacobian get_linear_jacobian( + dart::dynamics::MetaSkeleton* self, const dart::dynamics::BodyNode* _node) +{ + return self->getLinearJacobian(_node); +} + +dart::math::Jacobian get_jacobian( + dart::dynamics::MetaSkeleton* self, const dart::dynamics::BodyNode* _node) +{ + return self->getJacobian(_node); +} + +//==================================DART======================================== + +void Dart(pybind11::module& m) +{ + py::class_< + dart::dynamics::Skeleton, + std::shared_ptr>(m, "Skeleton") + .def("get_name", skeleton_get_name) + .def("get_positions", skeleton_get_positions) + .def("get_num_joints", skeleton_get_num_joints); + + py::class_< + dart::dynamics::MetaSkeleton, + std::shared_ptr>(m, "MetaSkeleton") + .def("get_name", metaskeleton_get_name) + .def("get_positions", metaskeleton_get_positions) + .def("get_num_joints", metaskeleton_get_num_joints) + .def("get_linear_jacobian", get_linear_jacobian) + .def("get_jacobian", get_jacobian); +} diff --git a/python/adapy/ik_bindings.cpp b/python/adapy/ik_bindings.cpp new file mode 100644 index 0000000..10e5623 --- /dev/null +++ b/python/adapy/ik_bindings.cpp @@ -0,0 +1,86 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace py = pybind11; + +aikido::constraint::dart::InverseKinematicsSampleable create_ik( + dart::dynamics::MetaSkeletonPtr armSkeleton, + aikido::statespace::dart::MetaSkeletonStateSpacePtr armSpace, + aikido::constraint::dart::TSR objectTSR, + dart::dynamics::BodyNode* body_node) +{ + auto goalTSR = std::make_shared(objectTSR); + auto ik = dart::dynamics::InverseKinematics::create(body_node); + ik->setDofs(armSkeleton->getDofs()); + auto rng = std::unique_ptr( + new aikido::common::RNGWrapper(0)); + aikido::constraint::dart::InverseKinematicsSampleable ikSampleable( + armSpace, + armSkeleton, + goalTSR, + aikido::constraint::dart::createSampleableBounds( + armSpace, std::move(rng)), + ik, + 10); + return ikSampleable; +} + +//============================================================================== +// NOTE: These functions define the Python API for IKSampleable. + +std::unique_ptr create_sample_generator( + aikido::constraint::dart::InverseKinematicsSampleable* self) +{ + return self->createSampleGenerator(); +} + +//============================================================================== +// NOTE: These functions define the Python API for IKSampleGenerator. + +bool can_sample(aikido::constraint::SampleGenerator* self) +{ + return self->canSample(); +} + +Eigen::VectorXd sample( + aikido::constraint::SampleGenerator* self, + aikido::statespace::dart::MetaSkeletonStateSpacePtr armSpace) +{ + auto goalState = armSpace->createState(); + bool sampled = self->sample(goalState); + // Init to length-0 vector + Eigen::VectorXd positions; + if (!sampled) + return positions; + armSpace->convertStateToPositions(goalState, positions); + return positions; +} + +//==================================IK========================================== + +void IK(pybind11::module& m) +{ + m.def("create_ik", create_ik); + + py::class_< + aikido::constraint::dart::InverseKinematicsSampleable, + std::shared_ptr>( + m, "IKSampleable") + .def("create_sample_generator", create_sample_generator); + + py::class_(m, "IKSampleGenerator") + .def("can_sample", can_sample) + .def("sample", sample); + + py::class_< + dart::dynamics::BodyNode, + std::shared_ptr>(m, "BodyNode"); +} diff --git a/python/adapy/pr_tsr_bindings.cpp b/python/adapy/pr_tsr_bindings.cpp new file mode 100644 index 0000000..e47604a --- /dev/null +++ b/python/adapy/pr_tsr_bindings.cpp @@ -0,0 +1,55 @@ +#include +#include +#include +#include +#include +#include + +namespace py = pybind11; + +Eigen::Isometry3d vectorToIsometry(std::vector& poseVector); +Eigen::Isometry3d matrixToIsometry(Eigen::Matrix4d& poseMatrix); + +//============================================================================== +// NOTE: These functions define the Python API for TSR. + +Eigen::Matrix4d get_T0_w(aikido::constraint::dart::TSR* self) +{ + return self->mT0_w.matrix(); +} + +void set_T0_w(aikido::constraint::dart::TSR* self, Eigen::Matrix4d& pose) +{ + self->mT0_w = matrixToIsometry(pose); +} + +void set_Bw(aikido::constraint::dart::TSR* self, Eigen::MatrixXf& Bw) +{ + self->mBw = Bw.cast(); +} + +Eigen::Matrix4d get_Tw_e(aikido::constraint::dart::TSR* self) +{ + return self->mTw_e.matrix(); +} + +void set_Tw_e(aikido::constraint::dart::TSR* self, Eigen::Matrix4d& pose) +{ + self->mTw_e = matrixToIsometry(pose); +} + +//==================================TSR========================================= + +void Pr_Tsr(pybind11::module& m) +{ + m.def("get_default_TSR", &pr_tsr::getDefaultCanTSR); + + py::class_< + aikido::constraint::dart::TSR, + std::shared_ptr>(m, "TSR") + .def("get_T0_w", get_T0_w) + .def("set_T0_w", set_T0_w) + .def("set_Bw", set_Bw) + .def("get_Tw_e", get_Tw_e) + .def("set_Tw_e", set_Tw_e); +} diff --git a/python/tests/simple_trajectories.py b/python/tests/simple_trajectories.py new file mode 100755 index 0000000..1219dce --- /dev/null +++ b/python/tests/simple_trajectories.py @@ -0,0 +1,79 @@ +#!/usr/bin/env python + +import adapy +import rospy + +import pdb +from moveit_ros_planning_interface._moveit_roscpp_initializer import roscpp_init + +rospy.init_node("adapy_simple_traj") +roscpp_init('adapy_simple_traj', []) +rate = rospy.Rate(10) +IS_SIM = True + +if not rospy.is_shutdown(): + ada = adapy.Ada(IS_SIM) + if not IS_SIM: + ada.start_trajectory_executor() + viewer = ada.start_viewer("dart_markers/simple_trajectories", "map") + canURDFUri = "package://pr_assets/data/objects/can.urdf" + sodaCanPose = [1.0, 0.0, 0.73, 0, 0, 0, 1] + tableURDFUri = "package://pr_assets/data/furniture/uw_demo_table.urdf" + tablePose = [1., 0.0, 0.0, 0.707107, 0, 0, 0.707107] + world = ada.get_world() + can = world.add_body_from_urdf(canURDFUri, sodaCanPose) + table = world.add_body_from_urdf(tableURDFUri, tablePose) + + collision = ada.get_self_collision_constraint() + + arm_skeleton = ada.get_arm_skeleton() + positions = arm_skeleton.get_positions() + arm_state_space = ada.get_arm_state_space() + + positions2 = positions.copy() + positions3 = positions.copy() + positions4 = positions.copy() + positions2[0] += 0.5 + positions2[2] += 0.2 + positions3[0] += 1.5 + positions3[2] += 0.4 + positions4[1] -= 0.4 + positions4[2] += 0.6 + + waypoints = [(0.0, positions), (1.0, positions2), (2.0, positions3), (3.0, positions4)] + waypoints_rev = [(0.0, positions4), (1.0, positions3), (2.0, positions2), (3.0, positions)] + traj = ada.compute_joint_space_path(arm_state_space, waypoints) + traj_rev = ada.compute_joint_space_path( + arm_state_space, waypoints_rev) + + print("") + print("CONTINUE TO EXECUTE") + print("") + pdb.set_trace() + + ada.execute_trajectory(traj) + + print("") + print("CLOSING HAND") + print("") + PRESHAPE = [1.1, 1.1] + ada.get_hand().execute_preshape(PRESHAPE) + + print("") + print("CONTINUE TO EXECUTE REVERSE") + print("") + pdb.set_trace() + + ada.execute_trajectory(traj_rev) + + print("") + print("OPENING HAND") + print("") + ada.get_hand().open() + + print("") + print("DONE! CONTINUE TO EXIT") + print("") + pdb.set_trace() + if not IS_SIM: + ada.stop_trajectory_executor() diff --git a/python/tests/test_collisions.py b/python/tests/test_collisions.py new file mode 100755 index 0000000..57c74f7 --- /dev/null +++ b/python/tests/test_collisions.py @@ -0,0 +1,64 @@ +#!/usr/bin/env python + +import adapy +import rospy + +from moveit_ros_planning_interface._moveit_roscpp_initializer import roscpp_init + +# import pdb +# pdb.set_trace() + +rospy.init_node("adapy_simple_traj") +roscpp_init('adapy_simple_traj', []) +rate = rospy.Rate(10) + +ada = adapy.Ada(True) +viewer = ada.start_viewer("dart_markers/simple_trajectories", "map") +canURDFUri = "package://pr_assets/data/objects/can.urdf" +sodaCanPose = [0.5, 0.0, 0.73, 0, 0, 0, 1] +tableURDFUri = "package://pr_assets/data/furniture/uw_demo_table.urdf" +tablePose = [0.5, 0.0, 0.0, 0.707107, 0, 0, 0.707107] +world = ada.get_world() +can = world.add_body_from_urdf(canURDFUri, sodaCanPose) +table = world.add_body_from_urdf(tableURDFUri, tablePose) + +arm_skeleton = ada.get_arm_skeleton() +positions = arm_skeleton.get_positions() +arm_state_space = ada.get_arm_state_space() + + +collision_free_constraint = ada.set_up_collision_detection( + arm_state_space, arm_skeleton, [can, table]) +full_collision_free_constraint = ada.get_full_collision_constraint( + arm_state_space, arm_skeleton, collision_free_constraint) + +# test original position +safe = full_collision_free_constraint.is_satisfied( + arm_state_space, arm_skeleton, positions) +if not safe: + print("State state is not safe!") + +# test self-collision +positions2 = positions.copy() +positions2[1] = 0.4 +safe = full_collision_free_constraint.is_satisfied( + arm_state_space, arm_skeleton, positions2) +if not safe: + print("Self-collision!") + +# test robot arm collision +positions3 = positions.copy() +positions3[1] -= 0.4 +positions3[2] += 0.6 +safe = full_collision_free_constraint.is_satisfied( + arm_state_space, arm_skeleton, positions3) +if not safe: + print("Arm body is in collision!") + +# test robot hand collision +positions4 = positions.copy() +positions4[1] = 2.1 +safe = full_collision_free_constraint.is_satisfied( + arm_state_space, arm_skeleton, positions4) +if not safe: + print("Hand is in collision!") diff --git a/src/Ada.cpp b/src/Ada.cpp index 30a5e4b..3f8f3e1 100644 --- a/src/Ada.cpp +++ b/src/Ada.cpp @@ -9,12 +9,14 @@ #include #include +#include #include #include #include #include #include #include +#include #include #include #include @@ -40,6 +42,7 @@ using aikido::constraint::dart::TSR; using aikido::constraint::dart::TSRPtr; using aikido::control::TrajectoryExecutorPtr; using aikido::planner::kunzretimer::KunzRetimer; +using aikido::planner::parabolic::ParabolicSmoother; using aikido::robot::ConcreteManipulator; using aikido::robot::ConcreteManipulatorPtr; using aikido::robot::ConcreteRobot; @@ -362,6 +365,62 @@ void Ada::update() step(std::chrono::system_clock::now()); } +//============================================================================== +TrajectoryPtr Ada::computeRetimedJointSpacePath( + const aikido::statespace::dart::MetaSkeletonStateSpacePtr& stateSpace, + const std::vector>& waypoints) +{ + auto satisfied = std::make_shared(stateSpace); + + std::shared_ptr interpolator + = std::make_shared(stateSpace); + std::shared_ptr traj + = std::make_shared( + stateSpace, interpolator); + + for (auto& waypoint : waypoints) + { + auto state = stateSpace->createState(); + stateSpace->convertPositionsToState(waypoint.second, state); + traj->addWaypoint(waypoint.first, state); + } + + auto timedTrajectory = std::move( + postProcessPath(traj.get(), satisfied, ada::KunzParams())); + + return timedTrajectory; +} + +//============================================================================== +TrajectoryPtr Ada::computeSmoothJointSpacePath( + const aikido::statespace::dart::MetaSkeletonStateSpacePtr& stateSpace, + const std::vector>& waypoints, + const CollisionFreePtr& collisionFree) +{ + // Use the given constraint if one was passed. + TestablePtr constraint = collisionFree; + if (!constraint) + constraint = std::make_shared(stateSpace); + + std::shared_ptr interpolator + = std::make_shared(stateSpace); + std::shared_ptr traj + = std::make_shared( + stateSpace, interpolator); + + for (auto& waypoint : waypoints) + { + auto state = stateSpace->createState(); + stateSpace->convertPositionsToState(waypoint.second, state); + traj->addWaypoint(waypoint.first, state); + } + + auto smoothTrajectory = postProcessPath( + traj.get(), constraint, ParabolicSmoother::Params()); + + return smoothTrajectory; +} + //============================================================================== TrajectoryPtr Ada::planToConfiguration( const MetaSkeletonStateSpacePtr& space, diff --git a/src/AdaHand.cpp b/src/AdaHand.cpp index 5becec9..f885011 100644 --- a/src/AdaHand.cpp +++ b/src/AdaHand.cpp @@ -264,8 +264,6 @@ void AdaHand::ungrab() //============================================================================== std::future AdaHand::executePreshape(const std::string& preshapeName) { - using aikido::constraint::Satisfied; - boost::optional preshape = getPreshape(preshapeName); if (!preshape) @@ -276,8 +274,16 @@ std::future AdaHand::executePreshape(const std::string& preshapeName) throw std::runtime_error(message.str()); } + return executePreshape(preshape.get()); +} + +//============================================================================== +std::future AdaHand::executePreshape(const Eigen::Vector2d& preshape) +{ + using aikido::constraint::Satisfied; + auto goalState = mSpace->createState(); - mSpace->convertPositionsToState(preshape.get(), goalState); + mSpace->convertPositionsToState(preshape, goalState); auto satisfied = std::make_shared(mSpace);