Compare commits

..

24 Commits

Author SHA1 Message Date
qlin1806
35131ed59e attempt to merge newer changes 2024-08-21 16:35:22 -07:00
fe5bb31873 bug fix hand initialization 2024-08-20 19:26:34 +09:00
e2f7830e01 bug fix hand initialization 2024-08-20 19:16:23 +09:00
75e00b3111 general bug fix 2024-08-19 15:30:30 +09:00
0358b851df minor bug fix for franka hand again 2024-08-18 21:40:42 +09:00
27b89070aa minor general bug fix 2024-08-18 21:16:47 +09:00
9b2061ba01 minor general bug fix 2024-08-18 20:57:24 +09:00
900f6aa2e1 minor renaming of file and working coppelia node 2024-08-16 11:30:58 +09:00
94a32a0f0c driver and hand tested successful.. next is coppeliamirror node 2024-08-15 20:19:28 +09:00
058c123170 [package] update fix package manifest 2024-07-28 19:49:12 +09:00
db4b1ccd58 attempt to test python 2024-07-27 15:24:26 +09:00
66a45b9ece added robot ui from JuankaEmika 2024-07-27 14:02:42 +09:00
7dfd4d40b8 migration to ros2 done 2024-07-27 13:07:37 +09:00
f5552be8d6 attempt to port ros2 2024-07-26 12:59:23 +09:00
e72826aeff remove gripper debugging output 2024-07-23 19:01:16 +09:00
qlin1806
221ccd1602 update example hand config 2024-07-22 21:50:59 -07:00
qlin1806
c47db0892a added python interface 2024-07-22 21:33:07 -07:00
qlin1806
101c45c228 added gripper driver for service control 2024-07-22 05:25:28 -07:00
25e88f56ed stiffness frame bugfix 2024-07-22 08:54:55 +09:00
qlin1806
fce21f08b9 more optimization.. 2024-07-21 03:52:21 -07:00
qlin1806
46668deac2 added proper binding for python for dynamic 2024-07-20 18:24:23 -07:00
qlin1806
1de3c2cbeb rate optimization 2024-07-20 16:17:51 -07:00
qlin1806
79479ce982 minor uptimizeation 2024-07-20 16:06:49 -07:00
qlin960618
e263d34c0c Echo contact (#1)
* added cartesian interface

* general fix and optimization
2024-07-20 14:34:54 +09:00
47 changed files with 2208 additions and 1117 deletions

View File

@@ -1,59 +1,109 @@
cmake_minimum_required(VERSION 3.0.2)
cmake_minimum_required(VERSION 3.8)
project(sas_robot_driver_franka)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
#add_compile_options(-std=c++11)
add_compile_options(-Werror=return-type)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
#Add custom (non compiling) targets so launch scripts and python files show up in QT Creator's project view.
file(GLOB_RECURSE EXTRA_FILES */*)
#add_custom_target(${PROJECT_NAME}_OTHER_FILES ALL WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} SOURCES ${EXTRA_FILES})
add_custom_target(cfg ALL WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} SOURCES ${EXTRA_FILES})
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
sas_common
sas_clock
sas_robot_driver
sas_patient_side_manager
)
catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS roscpp rospy sas_common sas_clock sas_robot_driver
)
find_package(Franka REQUIRED)
find_package(pybind11 REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(sas_common REQUIRED)
find_package(sas_core REQUIRED)
find_package(sas_conversions REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(yaml-cpp REQUIRED)
include_directories(${EIGEN3_INCLUDE_DIR})
find_package(tf2_ros REQUIRED)
find_package(tf2 REQUIRED)
find_package(sas_robot_driver REQUIRED)
find_package(Franka REQUIRED)
find_package(sas_robot_driver_franka_interfaces REQUIRED) # Add this line
# To correctly find and link with QT
## To correctly find and link with QT
set(CMAKE_PREFIX_PATH $ENV{QT_PATH})
set(CMAKE_AUTOMOC ON)
set(CMAKE_AUTORCC ON)
set(CMAKE_AUTOUIC ON)
if(CMAKE_VERSION VERSION_LESS "3.7.0")
if (CMAKE_VERSION VERSION_LESS "3.7.0")
set(CMAKE_INCLUDE_CURRENT_DIR ON)
endif()
endif ()
find_package(Qt5 COMPONENTS Widgets REQUIRED)
find_package(QT NAMES Qt6 Qt5 REQUIRED COMPONENTS Widgets)
find_package(Qt${QT_VERSION_MAJOR} REQUIRED COMPONENTS Widgets)
##### CPP LIBRARY initial #####
include_directories(
include
constraints_manager/include
)
install(
DIRECTORY include/
DESTINATION include
)
ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
ament_export_dependencies(Eigen3 rclcpp geometry_msgs std_msgs
sas_common sas_core sas_conversions sas_robot_driver_franka_interfaces
tf2_ros tf2 sas_robot_driver)
##### CPP LIBRARY initial end #####
##### CPP LIBRARY ROBOT_DYNAMICS #####
add_library(${PROJECT_NAME}_robot_dynamics SHARED
src/robot_dynamics/qros_robot_dynamics_client.cpp
src/robot_dynamics/qros_robot_dynamics_server.cpp
)
ament_target_dependencies(${PROJECT_NAME}_robot_dynamics
rclcpp geometry_msgs std_msgs
sas_common sas_core sas_conversions
tf2_ros tf2 sas_robot_driver)
target_include_directories(${PROJECT_NAME}_robot_dynamics
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
target_link_libraries(${PROJECT_NAME}_robot_dynamics
-ldqrobotics
Eigen3::Eigen
)
install(
TARGETS ${PROJECT_NAME}_robot_dynamics # ${PROJECT_NAME}
EXPORT export_${PROJECT_NAME} #export_${PROJECT_NAME}
LIBRARY DESTINATION lib
#ARCHIVE DESTINATION lib
RUNTIME DESTINATION bin
INCLUDES DESTINATION include
)
##END## CPP LIBRARY ROBOT_DYNAMICS #####
##### CPP LIBRARY Motion Generation #####
add_library(MotionGenerator src/generator/motion_generator.cpp)
target_link_libraries(MotionGenerator Franka::Franka)
target_link_libraries(MotionGenerator Franka::Franka Eigen3::Eigen)
add_library(ConstraintsManager constraints_manager/src/constraints_manager.cpp)
target_link_libraries(ConstraintsManager Eigen3::Eigen)
install(
DIRECTORY constraints_manager/include/
DESTINATION include/constraints_manager
)
target_include_directories(ConstraintsManager
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/constraints_manager/include>
$<INSTALL_INTERFACE:include/constraints_manager>)
add_library(QuadraticProgramMotionGenerator src/generator/quadratic_program_motion_generator.cpp)
target_link_libraries(QuadraticProgramMotionGenerator
@@ -61,12 +111,18 @@ target_link_libraries(QuadraticProgramMotionGenerator
dqrobotics
ConstraintsManager)
add_library(CustomMotionGeneration src/generator/custom_motion_generation.cpp)
target_link_libraries(CustomMotionGeneration
qpOASES
dqrobotics
ConstraintsManager)
##### CPP LIBRARY Motion Generation end #####
##### CPP LIBRARY franka low level interface #####
add_library(robot_interface_franka src/joint/robot_interface_franka.cpp)
target_link_libraries(robot_interface_franka Franka::Franka
dqrobotics
@@ -80,106 +136,157 @@ target_link_libraries(robot_interface_hand Franka::Franka
dqrobotics)
############
## Build ###
############
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
include
include/generator
src/
src/dynamic_interface
src/hand
src/joint
${catkin_INCLUDE_DIRS}
constraints_manager/include
)
add_library(sas_robot_dynamic_provider src/dynamic_interface/sas_robot_dynamic_provider.cpp)
target_link_libraries(sas_robot_dynamic_provider dqrobotics)
##### CPP LIBRARY franka low level interface end #####
##### SAS Franka Robot Driver #####
add_library(sas_robot_driver_franka src/joint/sas_robot_driver_franka.cpp)
target_link_libraries(sas_robot_driver_franka
sas_robot_dynamic_provider
${PROJECT_NAME}_robot_dynamics
dqrobotics
dqrobotics-interface-json11
robot_interface_franka)
add_library(sas_robot_driver_franka_hand src/hand/sas_robot_driver_franka_hand.cpp)
target_link_libraries(sas_robot_driver_franka_hand
##### SAS Franka Robot Driver end #####
##### qros hand effector driver #####
add_library(qros_effector_driver_franka_hand src/hand/qros_effector_driver_franka_hand.cpp)
ament_target_dependencies(qros_effector_driver_franka_hand
rclcpp sas_common sas_core
sas_robot_driver_franka_interfaces
)
#ament_target_dependencies(${PROJECT_NAME}_robot_dynamics
# rclcpp geometry_msgs std_msgs
# sas_common sas_core sas_conversions
# tf2_ros tf2 sas_robot_driver)
target_link_libraries(qros_effector_driver_franka_hand
dqrobotics
Franka::Franka)
#target_include_directories(qros_effector_driver_franka_hand
# PUBLIC
# $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include/interface>
# $<INSTALL_INTERFACE:include/interface>)
add_library(sas_robot_driver_coppelia src/coppelia/sas_robot_driver_coppelia.cpp)
target_link_libraries(sas_robot_driver_coppelia
dqrobotics
dqrobotics-interface-vrep)
##### qros hand effector driver end #####
add_dependencies(sas_robot_driver_franka ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(sas_robot_driver_coppelia ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_executable(sas_robot_driver_coppelia_node src/sas_robot_driver_coppelia_node.cpp)
target_link_libraries(sas_robot_driver_coppelia_node
sas_robot_driver_coppelia
${catkin_LIBRARIES})
##### SAS Franka Robot Driver Node #####
add_executable(sas_robot_driver_franka_node src/sas_robot_driver_franka_node.cpp)
target_link_libraries(sas_robot_driver_franka_node
sas_robot_driver_franka
${catkin_LIBRARIES})
ament_target_dependencies(sas_robot_driver_franka_node
rclcpp sas_common sas_core
sas_robot_driver)
target_link_libraries(sas_robot_driver_franka_node sas_robot_driver_franka)
install(TARGETS
sas_robot_driver_franka_node
DESTINATION lib/${PROJECT_NAME})
##### SAS Franka Robot Hand Driver Node #####
add_executable(sas_robot_driver_franka_hand_node src/sas_robot_driver_franka_hand_node.cpp)
ament_target_dependencies(sas_robot_driver_franka_node
rclcpp sas_common sas_core)
target_link_libraries(sas_robot_driver_franka_hand_node
sas_robot_driver_franka_hand
${catkin_LIBRARIES})
qros_effector_driver_franka_hand)
install(TARGETS
sas_robot_driver_franka_hand_node
DESTINATION lib/${PROJECT_NAME})
##### Coppelia Mirror Node #####
add_executable(sas_robot_driver_franka_coppelia_node
src/sas_robot_driver_coppelia_node.cpp
src/coppelia/sas_robot_driver_coppelia.cpp
)
ament_target_dependencies(sas_robot_driver_franka_coppelia_node
rclcpp sas_common sas_core sas_conversions sas_robot_driver
)
target_link_libraries(sas_robot_driver_franka_coppelia_node
dqrobotics
dqrobotics-interface-json11
dqrobotics-interface-vrep
)
install(TARGETS
sas_robot_driver_franka_coppelia_node
DESTINATION lib/${PROJECT_NAME})
##### JuanEmika
add_executable(JuankaEmika
qt/configuration_window/main.cpp
qt/configuration_window/mainwindow.cpp
qt/configuration_window/mainwindow.ui
)
)
ament_target_dependencies(sas_robot_driver_franka_node
rclcpp sas_common sas_core
sas_robot_driver)
target_link_libraries(JuankaEmika PRIVATE Qt${QT_VERSION_MAJOR}::Widgets
dqrobotics
${catkin_LIBRARIES}
robot_interface_franka
)
)
if(QT_VERSION_MAJOR EQUAL 6)
if (QT_VERSION_MAJOR EQUAL 6)
qt_finalize_executable(JuankaEmika)
endif()
endif ()
install(TARGETS ${PROJECT_NAME}
DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
install(TARGETS
JuankaEmika
DESTINATION lib/${PROJECT_NAME})
##### PYBIND11 LIBRARY ROBOT_DYNAMICS #####
ament_python_install_package(${PROJECT_NAME})
pybind11_add_module(_qros_franka_robot_dynamics_py SHARED
src/robot_dynamics/qros_robot_dynamics_py.cpp
src/robot_dynamics/qros_robot_dynamics_client.cpp
src/robot_dynamics/qros_robot_dynamics_server.cpp
)
install(TARGETS sas_robot_driver_franka_node
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
target_include_directories(_qros_franka_robot_dynamics_py
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include/robot_dynamics>
$<INSTALL_INTERFACE:include/robot_dynamics>)
target_compile_definitions(_qros_franka_robot_dynamics_py PRIVATE IS_SAS_PYTHON_BUILD)
# https://github.com/pybind/pybind11/issues/387
target_link_libraries(_qros_franka_robot_dynamics_py PRIVATE ${PROJECT_NAME}_robot_dynamics -ldqrobotics)
install(TARGETS _qros_franka_robot_dynamics_py
DESTINATION "${PYTHON_INSTALL_DIR}/${PROJECT_NAME}"
)
##END## PYBIND11 LIBRARY ROBOT_DYNAMICS #####
install(
DIRECTORY include/
DESTINATION include
)
install(TARGETS sas_robot_driver_coppelia_node
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
##### LAUNCH FILES #####
install(DIRECTORY
launch
DESTINATION share/${PROJECT_NAME}/
)
install(TARGETS sas_robot_driver_franka_hand_node
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
##END## LAUNCH FILES #####
ament_package()
## Mark cpp header files for installation
install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
)

View File

@@ -1,7 +1,3 @@
"robot_ip_address": "172.16.0.2"
"robot_mode": "PositionControl"
"robot_speed": 20.0
"thread_sampling_time_nsec": 40000000
"q_min": [0.00]
"q_max": [0.04]
"thread_sampling_time_nsec": 20000000 # 20ms , 50Hz

View File

@@ -0,0 +1,139 @@
/*
# Copyright (c) 2023 Juan Jose Quiroz Omana
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Juan Jose Quiroz Omana, email: juanjqogm@gmail.com
#
# ################################################################
#
# Contributors:
# 1. Juan Jose Quiroz Omana (juanjqogm@gmail.com)
# - Adapted from sas_robot_driver_denso.cpp
# (https://github.com/SmartArmStack/sas_robot_driver_denso/blob/master/src/sas_robot_driver_denso.cpp)
#
# ################################################################
*/
#pragma once
#include <exception>
#include <tuple>
#include <atomic>
#include <vector>
#include <memory>
#include <dqrobotics/DQ.h>
#include <sas_core/sas_clock.hpp>
// #include <dqrobotics/interfaces/vrep/DQ_VrepRobot.h>
#include <dqrobotics/interfaces/vrep/DQ_VrepInterface.h>
#include <dqrobotics/interfaces/json11/DQ_JsonReader.h>
// #include <dqrobotics/robot_modeling/DQ_SerialManipulatorDH.h>
#include <thread>
#include <atomic>
#include <sas_robot_driver/sas_robot_driver_server.hpp>
#include <sas_robot_driver/sas_robot_driver_client.hpp>
#define VIRTUAL_ROBOT_SIMULATION_SAMPLING_TIME_SEC 0.002 // 2ms, 500Hz
#define REAL_ROBOT_INTERFACE_INIT_TIMEOUT_COUNT 500
using namespace DQ_robotics;
using namespace Eigen;
namespace qros
{
struct RobotDriverCoppeliaConfiguration
{
double thread_sampling_time_sec; // frontend vrep update rate
int vrep_port;
std::string vrep_ip;
std::vector<std::string> vrep_joint_names;
bool vrep_dynamically_enabled = false;
std::string robot_mode;
bool using_real_robot;
std::string robot_topic_prefix;
std::string robot_parameter_file_path;
// VectorXd q_min;
// VectorXd q_max;
};
class RobotDriverCoppelia
{
private:
enum ControlMode{
Position=0,
Velocity
};
RobotDriverCoppeliaConfiguration configuration_;
std::shared_ptr<Node> node_sptr_;
sas::Clock clock_;
std::atomic_bool* break_loops_;
bool _should_shutdown() const {return (*break_loops_);}
ControlMode robot_mode_;
std::shared_ptr<DQ_VrepInterface> vi_;
std::shared_ptr<sas::RobotDriverClient> real_robot_interface_ = nullptr;
std::shared_ptr<sas::RobotDriverServer> robot_provider_ = nullptr;
// backend thread for simulaton
/**
* Current simulation mechanism is not accounting for any robot dynamics, just the joint limits
*/
std::thread velocity_control_simulation_thread_;
VectorXd simulated_joint_positions_;
VectorXd simulated_joint_velocities_;
void start_simulation_thread(); // thread entry point
void _velocity_control_simulation_thread_main();
std::atomic_bool simulation_thread_started_{false};
bool initialized_ = false;
inline void _assert_initialized() const{
if (!initialized_){throw std::runtime_error("[RobotDriverCoppelia] Robot driver not initialized");}
}
inline void _assert_is_alive() const{
if(!configuration_.using_real_robot && !simulation_thread_started_){throw std::runtime_error("[RobotDriverCoppelia] Robot Simulation is not alive");}
}
void _start_control_loop();
protected:
inline void _update_vrep_position(const VectorXd &joint_positions, const bool& force_update=false) const;
inline void _update_vrep_velocity(const VectorXd & joint_velocity) const;
public:
RobotDriverCoppelia(const RobotDriverCoppelia&)=delete;
RobotDriverCoppelia()=delete;
~RobotDriverCoppelia();
RobotDriverCoppelia(const std::shared_ptr<Node> &node_sptr, const RobotDriverCoppeliaConfiguration& configuration, std::atomic_bool* break_loops);
int start_control_loop(); // public entry point
void connect();
void disconnect();
void initialize();
void deinitialize();
std::tuple<VectorXd, VectorXd> joint_limits_;
};
}

View File

@@ -32,13 +32,13 @@
#pragma once
#include <array>
#include <Eigen/Core>
#include <Eigen/Dense>
#include <eigen3/Eigen/Core>
#include <eigen3/Eigen/Dense>
#include <vector>
#include <iostream>
#include <dqrobotics/solvers/DQ_QPOASESSolver.h>
#include <memory>
#include "constraints_manager.h"
#include <constraints_manager.h>
using namespace DQ_robotics;

View File

@@ -4,8 +4,8 @@
#include <array>
#include <Eigen/Core>
#include <Eigen/Dense>
#include <eigen3/Eigen/Core>
#include <eigen3/Eigen/Dense>
#include <franka/control_types.h>
#include <franka/duration.h>
#include <franka/robot.h>

View File

@@ -1,7 +1,7 @@
#pragma once
#include <array>
#include <Eigen/Core>
#include <Eigen/Dense>
#include <eigen3/Eigen/Core>
#include <eigen3/Eigen/Dense>
#include <vector>
#include <iostream>
#include <dqrobotics/solvers/DQ_QPOASESSolver.h>

View File

@@ -0,0 +1,138 @@
#pragma once
/*
# Copyright (c) 2023 Juan Jose Quiroz Omana
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Juan Jose Quiroz Omana, email: juanjqogm@gmail.com
#
# ################################################################
#
# Contributors:
# 1. Quenitin Lin
#
# ################################################################
*/
#include <exception>
#include <tuple>
#include <atomic>
#include <vector>
#include <memory>
#include <franka/robot.h>
#include <franka/gripper.h>
#include <thread>
#include <mutex>
// #define BLOCK_READ_IN_USED
// #define IN_TESTING
// #include <sas_robot_driver/sas_robot_driver.h>
#include <sas_core/sas_clock.hpp>
#include <rclcpp/service.hpp>
#include <rclcpp/rclcpp.hpp>
#ifdef IN_TESTING
#include "local/srv/grasp.hpp"
#include "local/srv/move.hpp"
#include "local/msg/gripper_state.hpp"
#else
#include <sas_robot_driver_franka_interfaces/srv/grasp.hpp>
#include <sas_robot_driver_franka_interfaces/srv/move.hpp>
#include <sas_robot_driver_franka_interfaces/msg/gripper_state.hpp>
#endif
// using namespace DQ_robotics;
// using namespace Eigen;
using namespace rclcpp;
using namespace sas_robot_driver_franka_interfaces;
namespace qros {
struct EffectorDriverFrankaHandConfiguration
{
std::string robot_ip;
double thread_sampeling_time_s = 1e8; // 10Hz
double default_force = 3.0;
double default_speed = 0.1;
double default_epsilon_inner = 0.005;
double default_epsilon_outer = 0.005;
};
class EffectorDriverFrankaHand{
private:
std::string driver_node_prefix_;
EffectorDriverFrankaHandConfiguration configuration_;
std::shared_ptr<Node> node_;
std::shared_ptr<franka::Gripper> gripper_sptr_;
std::atomic_bool* break_loops_;
bool _is_connected() const;
// thread specific functions
void _gripper_status_loop();
std::thread status_loop_thread_;
std::atomic_bool status_loop_running_{false};
Publisher<msg::GripperState>::SharedPtr gripper_status_publisher_;
std::mutex gripper_in_use_;
Service<srv::Grasp>::SharedPtr grasp_srv_;
Service<srv::Move>::SharedPtr move_srv_;
public:
bool _grasp_srv_callback(
const std::shared_ptr<srv::Grasp::Request> req,
std::shared_ptr<srv::Grasp::Response> res
);
bool _move_srv_callback(
const std::shared_ptr<srv::Move::Request> req,
std::shared_ptr<srv::Move::Response> res
);
EffectorDriverFrankaHand(const EffectorDriverFrankaHand&)=delete;
EffectorDriverFrankaHand()=delete;
~EffectorDriverFrankaHand();
EffectorDriverFrankaHand(
const std::string &driver_node_prefix,
const EffectorDriverFrankaHandConfiguration& configuration,
std::shared_ptr<Node> node,
std::atomic_bool* break_loops);
void start_control_loop();
void gripper_homing();
void connect() ;
void disconnect() noexcept;
void initialize() ;
void deinitialize() ;
};
} // qros

View File

@@ -40,12 +40,12 @@
#include <franka/robot.h>
#include <franka/gripper.h>
#include <franka/exception.h>
#include "generator/motion_generator.h"
#include <sas_robot_driver_franka/generator/motion_generator.h>
#include <sas_robot_driver_franka/generator/quadratic_program_motion_generator.h>
#include <sas_robot_driver_franka/generator/custom_motion_generation.h>
#include <thread>
#include "generator/quadratic_program_motion_generator.h"
#include <dqrobotics/robots/FrankaEmikaPandaRobot.h>
#include <atomic>
#include "generator/custom_motion_generation.h"
using namespace DQ_robotics;
using namespace Eigen;

View File

@@ -0,0 +1,96 @@
#pragma once
/*
# Copyright (c) 2024 Quenitin Lin
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Quenitin Lin
#
# ################################################################
#
# Contributors:
# 1. Quenitin Lin
#
# ################################################################
*/
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/node.hpp>
// #include <sas_common/sas_common.hpp>
#include <sas_conversions/sas_conversions.hpp>
#include <geometry_msgs/msg/wrench_stamped.hpp>
#include <geometry_msgs/msg/transform.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.h>
#include <tf2/time.h>
// #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <geometry_msgs/msg/pose.hpp>
#include <std_msgs/msg/header.hpp>
#include <dqrobotics/DQ.h>
#define BUFFER_DURATION_DEFAULT_S 2.0 // 2 second
using namespace rclcpp;
namespace qros {
using namespace DQ_robotics;
class RobotDynamicsClient {
private:
std::shared_ptr<Node> node_;
std::string topic_prefix_;
std::string child_frame_id_;
std::string parent_frame_id_;
Subscription<geometry_msgs::msg::WrenchStamped>::SharedPtr subscriber_cartesian_stiffness_;
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
static geometry_msgs::msg::Transform _dq_to_geometry_msgs_transform(const DQ& pose) ;
Vector3d last_stiffness_force_;
Vector3d last_stiffness_torque_;
DQ last_stiffness_frame_pose_;
void _callback_cartesian_stiffness(const geometry_msgs::msg::WrenchStamped &msg);
static DQ _geometry_msgs_transform_to_dq(const geometry_msgs::msg::Transform& transform);
public:
RobotDynamicsClient() = delete;
RobotDynamicsClient(const RobotDynamicsClient&) = delete;
// #ifdef BUILD_PYBIND
// explicit RobotDynamicsClient(const std::string& node_prefix):RobotDynamicsClient(sas::common::get_static_node_handle(),node_prefix){}
// #endif
explicit RobotDynamicsClient(const std::shared_ptr<Node> &node, const std::string& topic_prefix="GET_FROM_NODE");
VectorXd get_stiffness_force();
VectorXd get_stiffness_torque();
DQ get_stiffness_frame_pose();
bool is_enabled() const;
std::string get_topic_prefix() const {return topic_prefix_;}
};
} // namespace sas

View File

@@ -0,0 +1,90 @@
#pragma once
/*
# Copyright (c) 2024 Quenitin Lin
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Quenitin Lin
#
# ################################################################
#
# Contributors:
# 1. Quenitin Lin
#
# ################################################################
*/
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/node.hpp>
// #include <sas_common/sas_common.hpp>
#include <sas_conversions/sas_conversions.hpp>
#include <geometry_msgs/msg/wrench_stamped.hpp>
#include <geometry_msgs/msg/transform.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros//static_transform_broadcaster.h>
#include <geometry_msgs/msg/pose.hpp>
#include <std_msgs/msg/header.hpp>
#include <dqrobotics/DQ.h>
#define REDUCE_TF_PUBLISH_RATE 10
#define WORLD_FRAME_ID "world"
using namespace rclcpp;
namespace qros {
using namespace DQ_robotics;
class RobotDynamicsServer {
private:
unsigned int seq_ = 0;
std::shared_ptr<Node> node_;
std::string topic_prefix_;
std::string child_frame_id_;
std::string parent_frame_id_;
rclcpp::Publisher<geometry_msgs::msg::WrenchStamped>::SharedPtr publisher_cartesian_stiffness_;
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_base_tf_broadcaster_;
DQ world_to_base_tf_ = DQ(0);
static geometry_msgs::msg::Transform _dq_to_geometry_msgs_transform(const DQ& pose);
void _publish_base_static_tf();
public:
RobotDynamicsServer() = delete;
RobotDynamicsServer(const RobotDynamicsServer&) = delete;
// #ifdef BUILD_PYBIND
// explicit RobotDynamicsServer(const std::string& node_prefix):RobotDynamicsServer(sas::common::get_static_node_handle(),node_prefix){}
// #endif
explicit RobotDynamicsServer(const std::shared_ptr<Node> &node, const std::string& topic_prefix="GET_FROM_NODE");
void publish_stiffness(const DQ& base_to_stiffness, const Vector3d& force, const Vector3d& torque);
void set_world_to_base_tf(const DQ& world_to_base_tf);
bool is_enabled() const;
std::string get_topic_prefix() const {return topic_prefix_;}
};
} // namespace sas

View File

@@ -40,10 +40,10 @@
#include <dqrobotics/DQ.h>
#include <sas_robot_driver/sas_robot_driver.h>
#include "robot_interface_franka.h"
#include <ros/common.h>
#include "sas_robot_dynamic_provider.h"
#include <sas_core/sas_robot_driver.hpp>
#include <sas_robot_driver_franka/interfaces/robot_interface_franka.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sas_robot_driver_franka/robot_dynamic/qros_robot_dynamics_server.hpp>
using namespace DQ_robotics;
using namespace Eigen;
@@ -60,17 +60,20 @@ struct RobotDriverFrankaConfiguration
int port;
double speed;
RobotInterfaceFranka::FrankaInterfaceConfiguration interface_configuration;
DQ robot_reference_frame = DQ(0);
};
class RobotDriverFranka: public RobotDriver
class RobotDriverFranka: public sas::RobotDriver
{
private:
std::shared_ptr<Node> node_;
RobotDriverFrankaConfiguration configuration_;
std::shared_ptr<RobotInterfaceFranka> robot_driver_interface_sptr_ = nullptr;
RobotDynamicProvider* robot_dynamic_provider_;
std::shared_ptr<qros::RobotDynamicsServer> robot_dynamic_provider_sptr_;
//Joint positions
VectorXd joint_positions_;
@@ -86,6 +89,8 @@ private:
void _update_stiffness_contact_and_pose() const;
public:
//const static int SLAVE_MODE_JOINT_CONTROL;
//const static int SLAVE_MODE_END_EFFECTOR_CONTROL;
@@ -95,7 +100,8 @@ public:
~RobotDriverFranka();
RobotDriverFranka(
RobotDynamicProvider* robot_dynamic_provider,
const std::shared_ptr<Node> &node,
const std::shared_ptr<qros::RobotDynamicsServer> &robot_dynamic_provider,
const RobotDriverFrankaConfiguration& configuration,
std::atomic_bool* break_loops
);

View File

@@ -6,12 +6,5 @@
<rosparam file="$(find sas_robot_driver_franka)/cfg/sas_robot_driver_franka_hand_1.yaml" command="load"
/>
</node>
</launch>

View File

@@ -0,0 +1,45 @@
from launch import LaunchDescription
from launch_ros.actions import Node
import os
def generate_launch_description():
return LaunchDescription([
Node(
package='sas_robot_driver_franka',
executable='sas_robot_driver_franka_node',
name='arm3',
parameters=[{
"robot_ip_address": "172.16.0.4",
"thread_sampling_time_sec": 0.004,
# "thread_sampling_time_nsec": 4000000,
"q_min": [-2.3093, -1.5133, -2.4937, -2.7478, -2.4800, 0.8521, -2.6895],
"q_max": [2.3093, 1.5133, 2.4937, -0.4461, 2.4800, 4.2094, 2.6895],
"force_upper_limits_scaling_factor": 4.0,
"upper_torque_threshold": [40.0, 40.0, 40.0, 40.0, 40.0, 40.0, 40.0],
"upper_force_threshold": [40.0, 40.0, 40.0, 40.0, 40.0, 40.0],
"robot_mode": "VelocityControl",
"robot_parameter_file_path": os.environ["ROBOT_3_JSON_PATH"]
}],
output="screen"
),
Node(
package='sas_robot_driver_franka',
executable='sas_robot_driver_franka_coppelia_node',
name='arm3_coppelia',
parameters=[{
"thread_sampling_time_sec": 0.008,
"vrep_ip": os.environ["VREP_IP"],
"vrep_port": 20012,
"vrep_dynamically_enabled": True,
"using_real_robot": True,
"vrep_joint_names": ["Franka_joint1#1", "Franka_joint2#1", "Franka_joint3#1", "Franka_joint4#1",
"Franka_joint5#1", "Franka_joint6#1", "Franka_joint7#1"],
"robot_topic_prefix": "/arm3",
"robot_mode": "VelocityControl",
"robot_parameter_file_path": os.environ["ROBOT_3_JSON_PATH"]
}],
output="screen"
),
])

View File

@@ -0,0 +1,24 @@
from launch import LaunchDescription
from launch_ros.actions import Node
import os
def generate_launch_description():
return LaunchDescription([
Node(
package='sas_robot_driver_franka',
executable='sas_robot_driver_franka_hand_node',
name='arm3_hand',
parameters=[{
"robot_ip_address": "172.16.0.2",
# "thread_sampling_time_nsec": 20000000, # 20ms , 50Hz
"thread_sampling_time_sec": 0.02,
"default_force": 2.0,
"default_speed": 0.07,
"default_epsilon_inner": 0.007,
"default_epsilon_outer": 0.007,
}],
output="screen"
),
])

View File

@@ -0,0 +1,27 @@
from launch import LaunchDescription
from launch_ros.actions import Node
import os
def generate_launch_description():
return LaunchDescription([
Node(
package='sas_robot_driver_franka',
executable='sas_robot_driver_franka_coppelia_node',
name='arm3_coppelia',
parameters=[{
"thread_sampling_time_sec": 0.008,
"vrep_ip": os.environ["VREP_IP"],
"vrep_port": 20012,
"vrep_dynamically_enabled": True,
"using_real_robot": False,
"vrep_joint_names": ["Franka_joint1#1", "Franka_joint2#1", "Franka_joint3#1", "Franka_joint4#1",
"Franka_joint5#1", "Franka_joint6#1", "Franka_joint7#1"],
"robot_topic_prefix": "/arm3",
"robot_mode": "VelocityControl",
"robot_parameter_file_path": os.environ["ROBOT_3_JSON_PATH"]
}],
output="screen"
),
])

View File

@@ -1,84 +1,32 @@
<?xml version="1.0"?>
<package format="2">
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>sas_robot_driver_franka</name>
<version>0.0.0</version>
<description>The sas_driver_franka package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="moonshot@todo.todo">moonshot</maintainer>
<license>LGPLv3</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<depend>rclcpp</depend>
<depend>rclpy</depend>
<depend>tf2_ros</depend>
<depend>tf2</depend>
<depend>std_msgs</depend>
<depend>sas_core</depend>
<depend>sas_robot_driver</depend>
<depend>sas_common</depend>
<depend>sas_robot_driver_franka_interface</depend>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/sas_driver_franka</url> -->
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>sas_clock</build_depend>
<build_depend>sas_robot_driver</build_depend>
<build_depend>sas_common</build_depend>
<build_depend>sas_patient_side_manager</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<build_export_depend>sas_clock</build_export_depend>
<build_export_depend>sas_robot_driver</build_export_depend>
<build_export_depend>sas_common</build_export_depend>
<build_export_depend>sas_patient_side_manager</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>sas_clock</exec_depend>
<exec_depend>sas_robot_driver</exec_depend>
<exec_depend>sas_common</exec_depend>
<exec_depend>sas_patient_side_manager</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@@ -7,7 +7,7 @@
#include <QMainWindow>
#include "qspinbox.h"
#include "robot_interface_franka.h"
#include <sas_robot_driver_franka/interfaces/robot_interface_franka.hpp>
QT_BEGIN_NAMESPACE
namespace Ui { class MainWindow; }

View File

@@ -0,0 +1,206 @@
"""
"""
from typing import Union
from sas_robot_driver_franka._qros_franka_robot_dynamics_py import RobotDynamicsClient, RobotDynamicsServer
import rclpy
from rclpy.node import Node
from rclpy.client import Client
from sas_common import rclcpp_init, rclcpp_Node, rclcpp_spin_some, rclcpp_shutdown
from sas_robot_driver_franka_interfaces.srv import Move, Grasp
from sas_robot_driver_franka_interfaces.msg import GripperState
import os
import threading
from queue import Queue
import time
import struct
MOVE_TOPIC_SUFFIX = "move"
GRASP_TOPIC_SUFFIX = "grasp"
STATUS_TOPIC_SUFFIX = "gripper_status"
class FrankaGripperInterface:
"""
Non blocking interface to control the Franka gripper
"""
def __init__(self, node: Node, robot_prefix):
self.robot_prefix = robot_prefix
self.node = node
self.move_service = node.create_client(Move, os.path.join(robot_prefix, MOVE_TOPIC_SUFFIX))
self._moving = False
self.grasp_service = node.create_client(Grasp, os.path.join(robot_prefix, GRASP_TOPIC_SUFFIX))
self._grasping = False
self.status_subscriber = node.create_subscription(GripperState, os.path.join(robot_prefix, STATUS_TOPIC_SUFFIX),
self._status_callback, 10)
self.service_future: Union[rclpy.Future, None] = None
# gripper state
self.state_width = None
self.state_max_width = None
self.state_temperature = None
self.state_is_grasped = None
self.spin_handler = self._default_spin_handler
def _default_spin_handler(self):
rclpy.spin_once(self.node)
def _is_service_ready(self, service: Client):
try:
# self.node.get_logger().info("Waiting for service: " + service.service_name)
ret = service.wait_for_service(timeout_sec=0.1)
return ret
except Exception as e:
self.node.get_logger().info("Service error: " + service.service_name + ": " + str(e))
return False
def is_enabled(self):
if self.state_width is None:
return False
if not self._is_service_ready(self.move_service):
return False
if not self._is_service_ready(self.grasp_service):
return False
return True
def _status_callback(self, msg: GripperState):
self.state_width = msg.width
self.state_max_width = msg.max_width
self.state_temperature = msg.temperature
self.state_is_grasped = msg.is_grasped
def move(self, width, speed=0):
"""
Move the gripper to a specific width
:param width: width in meters
:param speed: speed in meters per second
:return: None
"""
if self.is_busy():
raise Exception("Gripper is already moving or grasping, please wait until the previous action is finished")
self._move(width, speed)
def grasp(self, width, force=0, speed=0, epsilon_inner=0, epsilon_outer=0):
"""
Grasp an object with the gripper
:param width:
:param force:
:param speed:
:param epsilon_inner:
:param epsilon_outer:
:return:
"""
if self.is_busy():
raise Exception("Gripper is already moving or grasping, please wait until the previous action is finished")
self._grasp(width, force, speed, epsilon_inner, epsilon_outer)
def get_max_width(self):
""" Get the maximum width of the gripper """
if not self.is_enabled():
raise Exception("Gripper is not enabled")
return self.state_max_width
def get_width(self):
""" Get the current width of the gripper """
if not self.is_enabled():
raise Exception("Gripper is not enabled")
return self.state_width
def get_temperature(self):
""" Get the temperature of the gripper """
if not self.is_enabled():
raise Exception("Gripper is not enabled")
return self.state_temperature
def is_grasped(self):
""" Check if an object is grasped """
if not self.is_enabled():
raise Exception("Gripper is not enabled")
return self.state_is_grasped
def is_moving(self):
""" Check if the gripper is currently moving """
return self._moving
def is_grasping(self):
""" Check if the gripper is currently grasping """
return self._grasping
def is_busy(self):
""" Check if the gripper is currently moving or grasping """
return self._moving or self._grasping or self.service_future is not None
def is_done(self):
""" Check if the gripper is done moving or grasping """
if not self.is_busy():
self.node.get_logger().warn("Gripper is not moving or grasping")
return False
else:
if self.service_future is not None:
if self.service_future.done():
return True
return False
else:
return True
def get_result(self):
"""
Get the result of the last action
:return:
"""
if self.service_future is not None:
if self.service_future.done():
response = self.service_future.result()
if isinstance(response, Move.Response):
self._moving = False
elif isinstance(response, Grasp.Response):
self._grasping = False
else:
raise Exception("Invalid response type")
self.service_future = None
return response.success
else:
raise Exception("No result available")
else:
raise Exception("No result available")
def wait_until_done(self):
"""
Wait until the gripper is done moving or grasping
:return: success
"""
if not self.is_enabled():
raise Exception("Gripper is not enabled")
if not self.is_busy():
return
while not self.is_done():
self.spin_handler()
time.sleep(0.01)
def _move(self, width, speed):
self._moving = True
# self.node.get_logger().info("Moving gripper to width: " + str(width) + " speed: " + str(speed))
request = Move.Request()
request.width = float(width)
request.speed = float(speed)
# self.node.get_logger().info("Calling move service")
self.service_future = self.move_service.call_async(request)
def _grasp(self, width, force, speed, epsilon_inner, epsilon_outer):
self._grasping = True
# self.node.get_logger().info("Grasping object at width: " + str(width) + " force: " + str(force) + " speed: " + str(speed))
request = Grasp.Request()
request.width = float(width)
request.force = float(force)
request.speed = float(speed)
request.epsilon_inner = float(epsilon_inner)
request.epsilon_outer = float(epsilon_outer)
# self.node.get_logger().info("Calling grasp service")
self.service_future = self.grasp_service.call_async(request)
def set_spin_handler(self, spin_handler):
self.spin_handler = spin_handler

View File

@@ -0,0 +1,74 @@
import threading
from sas_common import rclcpp_init, rclcpp_Node, rclcpp_spin_some, rclcpp_shutdown
import rclpy
from sas_robot_driver_franka import FrankaGripperInterface
import time
def main_loop(node):
iteration_ = 0
node_name = node.get_name()
hand1 = FrankaGripperInterface(node, "/franka_hand_1")
logger = rclpy.node.get_logger(node_name)
while not hand1.is_enabled():
logger.info("Waiting for gripper to be enabled...")
rclcpp_spin_some(node)
time.sleep(0.1)
rclpy.node.get_logger(node_name).info("Gripper enabled!")
def spin_all(node_):
while rclpy.ok():
rclcpp_spin_some(node_)
rclpy.spin_once(node_, timeout_sec=0.1)
time.sleep(0.1)
thread = threading.Thread(target=spin_all, args=(node, ), daemon=True)
thread.start()
rate = node.create_rate(2)
while rclpy.ok():
logger.info("Main loop running...")
# Get the temperature of the gripper
temperature = hand1.get_temperature()
logger.info(f"Temperature: {temperature}")
max_width = hand1.get_max_width()
logger.info(f"Max width: {max_width}")
width = hand1.get_width()
logger.info(f"Width: {width}")
is_grasped = hand1.is_grasped()
logger.info(f"Is grasped: {is_grasped}")
is_moving = hand1.is_moving()
logger.info(f"Is moving: {is_moving}")
is_grasping = hand1.is_grasping()
logger.info(f"Is grasping: {is_grasping}")
logger.warn("calling move(0.01)")
if not hand1.is_busy():
hand1.grasp(0.01)
else:
logger.warn("Gripper is busy. Waiting...")
result_ready = hand1.is_done()
if not result_ready:
logger.info("Waiting for gripper to finish moving...")
else:
result = hand1.get_result()
logger.info(f"Result: {result}")
# Check if there is a response in the queue
iteration_ += 1
rate.sleep()
rclpy.shutdown()
thread.join()
if __name__ == "__main__":
rclpy.init()
node_name_ = "example_gripper_control_node"
NODE = rclpy.create_node(node_name_)
main_loop(NODE)

View File

@@ -0,0 +1,29 @@
import rospy
from sas_robot_driver_franka import RobotDynamicsServer
import dqrobotics as dql
import numpy as np
if __name__ == "__main__":
rospy.init_node("dummy_robot_dynamics_provider")
dynam_provider = RobotDynamicsProvider("/franka1")
t = dql.DQ([0, 0, 1])
r = dql.DQ([1, 0, 0, 0])
base_pose = r + 0.5 * dql.E_ * t * r
dynam_provider.set_world_to_base_tf(base_pose)
t_ = 0
rospy.loginfo("Publishing dummy robot dynamics")
r = dql.DQ([0, 0, 0, 1])
rate = rospy.Rate(100)
dummy_force = np.random.rand(3) * 100
dummy_torque = np.random.rand(3) * 10
while not rospy.is_shutdown():
t = dql.DQ([1, 2, 1]) + dql.i_ * np.sin(t_/2/np.pi) + dql.j_ * np.cos(t_/2/np.pi)
ee_pose = r + 0.5 * dql.E_ * t * r
dummy_force = dummy_force * 0.9 + np.random.rand(3) * 10
dummy_torque = dummy_torque * 0.9 + np.random.rand(3) * 1
dynam_provider.publish_stiffness(ee_pose, dummy_force, dummy_torque)
rate.sleep()
t_ += 0.01

View File

@@ -0,0 +1,30 @@
import rospy
from sas_robot_driver_franka import RobotDynamicsInterface
import dqrobotics as dql
import numpy as np
from dqrobotics.interfaces.vrep import DQ_VrepInterface
vrep = DQ_VrepInterface()
vrep.connect("192.168.10.103", 19997, 100, 10)
if __name__ == "__main__":
rospy.init_node("dummy_robot_dynamics_subscriber")
dynam_provider = RobotDynamicsInterface("/franka1")
while not dynam_provider.is_enabled():
rospy.loginfo("Waiting for robot dynamics provider to be enabled")
rospy.sleep(1)
rospy.loginfo("Subscribing to dummy robot dynamics")
rate = rospy.Rate(50)
while not rospy.is_shutdown():
force = dynam_provider.get_stiffness_force()
torque = dynam_provider.get_stiffness_torque()
ee_pose = dynam_provider.get_stiffness_frame_pose()
vrep.set_object_pose("xd1", ee_pose)
rospy.loginfo("EE Pose: %s", ee_pose)
rospy.loginfo("Force: %s", force)
rospy.loginfo("Torque: %s", torque)
rate.sleep()

View File

@@ -1,253 +1,247 @@
#include "sas_robot_driver_coppelia.h"
#include <sas_robot_driver_franka/coppelia/sas_robot_driver_coppelia.hpp>
namespace sas
namespace qros
{
RobotDriverCoppelia::~RobotDriverCoppelia() {
deinitialize();
disconnect();
}
RobotDriverCoppelia::RobotDriverCoppelia(const RobotDriverCoppeliaConfiguration &configuration, std::atomic_bool *break_loops):
RobotDriver(break_loops),
RobotDriverCoppelia::RobotDriverCoppelia(const std::shared_ptr<Node> &node_sptr, const RobotDriverCoppeliaConfiguration &configuration, std::atomic_bool *break_loops):
configuration_(configuration),
robot_mode_(configuration.robot_mode),
jointnames_(configuration.jointnames),
mirror_mode_(configuration.mirror_mode),
dim_configuration_space_(configuration.jointnames.size()),
real_robot_topic_prefix_(configuration.real_robot_topic_prefix)
node_sptr_(node_sptr),
clock_(configuration.thread_sampling_time_sec),
break_loops_(break_loops),
robot_mode_(ControlMode::Position),
vi_(std::make_shared<DQ_VrepInterface>())
{
vi_ = std::make_shared<DQ_VrepInterface>();
desired_joint_velocities_ = VectorXd::Zero(dim_configuration_space_);
auto nodehandle = ros::NodeHandle();
std::cout<<"RobotDriverCoppelia::Rostopic: "<<"/"+real_robot_topic_prefix_<<std::endl;
franka1_ros_ = std::make_shared<sas::RobotDriverInterface>(nodehandle, "/"+real_robot_topic_prefix_);
}
VectorXd RobotDriverCoppelia::get_joint_positions()
{
return current_joint_positions_;
}
void RobotDriverCoppelia::set_target_joint_positions(const VectorXd &desired_joint_positions_rad)
{
desired_joint_positions_ = desired_joint_positions_rad;
}
VectorXd RobotDriverCoppelia::get_joint_velocities()
{
return current_joint_velocities_;
}
void RobotDriverCoppelia::set_target_joint_velocities(const VectorXd &desired_joint_velocities)
{
desired_joint_velocities_ = desired_joint_velocities;
}
VectorXd RobotDriverCoppelia::get_joint_forces()
{
return current_joint_forces_;
}
RobotDriverCoppelia::~RobotDriverCoppelia()=default;
void RobotDriverCoppelia::connect()
{
vi_->connect(configuration_.ip, configuration_.port, 500, 10);
vi_->set_joint_target_velocities(jointnames_, VectorXd::Zero(dim_configuration_space_));
std::cout<<"RobotDriverCoppelia::Connecting..."<<std::endl;
}
void RobotDriverCoppelia::disconnect()
{
vi_->disconnect();
if (joint_velocity_control_mode_thread_.joinable())
// should initialize robot driver interface to real robot
DQ_SerialManipulatorDH smdh = DQ_JsonReader::get_from_json<DQ_SerialManipulatorDH>(configuration_.robot_parameter_file_path);
joint_limits_ = {smdh.get_lower_q_limit(),smdh.get_upper_q_limit()};
if(configuration_.using_real_robot)
{
joint_velocity_control_mode_thread_.join();
}
if (joint_velocity_control_mirror_mode_thread_.joinable())
{
joint_velocity_control_mirror_mode_thread_.join();
}
std::cout<<"RobotDriverCoppelia::Disconnected."<<std::endl;
}
void RobotDriverCoppelia::initialize()
{
vi_->start_simulation();
if (mirror_mode_ == false)
{
_start_joint_velocity_control_thread();
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::Using real robot, Instantiating robot interface to real driver at ["+configuration_.robot_topic_prefix+"].");
real_robot_interface_ = std::make_shared<sas::RobotDriverClient>(node_sptr_, configuration_.robot_topic_prefix);
}else{
_start_joint_velocity_control_mirror_thread();
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::Using simulation robot, simulation mode is set to "+ configuration_.robot_mode);
robot_provider_ = std::make_shared<sas::RobotDriverServer>(node_sptr_, configuration_.robot_topic_prefix);
std::string _mode_upper = configuration_.robot_mode;
std::transform(_mode_upper.begin(), _mode_upper.end(), _mode_upper.begin(), ::toupper);
if(_mode_upper == "POSITIONCONTROL"){
robot_mode_ = ControlMode::Position;
}else if(_mode_upper == "VELOCITYCONTROL"){
robot_mode_ = ControlMode::Velocity;
}else{
throw std::invalid_argument("[" + std::string(node_sptr_->get_name()) + "]::Robot mode must be either 'position' or 'velocity'");
}
std::cout<<"RobotDriverCoppelia::Velocity loop running..."<<std::endl;
}
}
void RobotDriverCoppelia::deinitialize()
{
vi_->set_joint_target_velocities(jointnames_, VectorXd::Zero(dim_configuration_space_));
vi_->stop_simulation();
finish_motion();
std::cout<<"RobotDriverCoppelia::Deinitialized."<<std::endl;
void RobotDriverCoppelia::_update_vrep_position(const VectorXd &joint_positions, const bool& force_update) const{
if(configuration_.vrep_dynamically_enabled){
if(force_update){
vi_->set_joint_positions(configuration_.vrep_joint_names, joint_positions);
}
vi_->set_joint_target_positions(configuration_.vrep_joint_names, joint_positions);
}else{
vi_->set_joint_positions(configuration_.vrep_joint_names, joint_positions);
}
}
void RobotDriverCoppelia::_update_robot_state(const VectorXd &q, const VectorXd &q_dot, const VectorXd &forces)
{
current_joint_positions_ = q;
current_joint_velocities_ = q_dot;
current_joint_forces_ = forces;
void RobotDriverCoppelia::_update_vrep_velocity(const VectorXd & joint_velocity) const{
if(!configuration_.vrep_dynamically_enabled){
throw std::runtime_error("[RobotDriverCoppelia]::[_update_vrep_velocity]::Vrep is not dynamically enabled");
}
vi_->set_joint_target_velocities(configuration_.vrep_joint_names, joint_velocity);
}
void RobotDriverCoppelia::finish_motion()
{
for (int i=0;i<1000;i++)
void RobotDriverCoppelia::_start_control_loop(){
clock_.init();
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::Starting control loop...");
while(!_should_shutdown()){
clock_.update_and_sleep();
rclcpp::spin_some(node_sptr_);
if(!rclcpp::ok()){break_loops_->store(true);}
if(configuration_.using_real_robot){
// real_robot_interface_
auto joint_position = real_robot_interface_->get_joint_positions();
_update_vrep_position(joint_position);
}else{
// robot_provider_
VectorXd target_joint_positions;
auto current_joint_positions = vi_->get_joint_positions(configuration_.vrep_joint_names);
VectorXd current_joint_velocity;
if(robot_provider_->is_enabled()) {
if(robot_mode_ == ControlMode::Velocity)
{
set_target_joint_positions(current_joint_positions_);
set_target_joint_velocities(VectorXd::Zero(dim_configuration_space_));
std::this_thread::sleep_for(std::chrono::milliseconds(1));
if(robot_provider_->is_enabled(sas::RobotDriver::Functionality::VelocityControl)) {
simulated_joint_velocities_ = robot_provider_->get_target_joint_velocities();
current_joint_velocity = simulated_joint_velocities_;
// try{_update_vrep_velocity(simulated_joint_velocities_);}catch (...){}
}
finish_motion_ = true;
else{
RCLCPP_DEBUG_STREAM(node_sptr_->get_logger(), "::Velocity control is not enabled.");
}
target_joint_positions = simulated_joint_positions_;
}else{
target_joint_positions = robot_provider_->get_target_joint_positions();
}
}else {
target_joint_positions = current_joint_positions;
}
_update_vrep_position(target_joint_positions);
robot_provider_->send_joint_states(current_joint_positions, current_joint_velocity, VectorXd());
robot_provider_->send_joint_limits(joint_limits_);
}
}
}
void RobotDriverCoppelia::_start_joint_velocity_control_mode()
{
int RobotDriverCoppelia::start_control_loop(){
try{
finish_motion_ = false;
VectorXd q = vi_->get_joint_positions(jointnames_);
VectorXd q_dot = vi_->get_joint_velocities(jointnames_);
VectorXd forces = vi_->get_joint_torques(jointnames_);
_update_robot_state(q, q_dot, forces);
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::Waiting to connect with coppelia...");
connect();
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::Connected to coppelia.");
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::Initializing...");
initialize();
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::initialized.");
desired_joint_positions_ = q;
while(true)
{
VectorXd q = vi_->get_joint_positions(jointnames_);
VectorXd q_dot = vi_->get_joint_velocities(jointnames_);
VectorXd forces = vi_->get_joint_torques(jointnames_);
_update_robot_state(q, q_dot, forces);
if (robot_mode_ == std::string("VelocityControl"))
{
vi_->set_joint_target_velocities(jointnames_, desired_joint_velocities_);
}
else if (robot_mode_ == std::string("PositionControl"))
{
vi_->set_joint_target_positions(jointnames_, desired_joint_positions_);
}
if (finish_motion_) {
finish_motion_ = false;
return;
}
}
_start_control_loop();
}
catch(const std::exception& e)
{
std::cout<<"RobotDriverCoppelia::sas_robot_coppelia_driver::_start_joint_velocity_control_mode(). Error or exception caught " << e.what()<<std::endl;
RCLCPP_WARN_STREAM(node_sptr_->get_logger(), "::Error or exception caught::" << e.what());
}
catch(...)
{
std::cout<<"RobotDriverCoppelia::sas_robot_coppelia_driver::_start_joint_velocity_control_mode(). Error or exception caught " <<std::endl;
RCLCPP_WARN_STREAM(node_sptr_->get_logger(), "::Unexpected error or exception caught");
}
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::Deinitializing...");
deinitialize();
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::deinitialized.");
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::Disconnecting from coppelia...");
disconnect();
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::Disconnected from coppelia.");
return 0;
}
void RobotDriverCoppelia::_start_joint_velocity_control_thread()
{
finish_motion_ = false;
if (joint_velocity_control_mode_thread_.joinable())
{
joint_velocity_control_mode_thread_.join();
void RobotDriverCoppelia::connect(){
auto ret = vi_->connect(configuration_.vrep_ip, configuration_.vrep_port, 100, 10);
if(!ret){
throw std::runtime_error("[RobotDriverCoppelia]::connect::Could not connect to Vrep");
}
if (joint_velocity_control_mirror_mode_thread_.joinable())
{
joint_velocity_control_mirror_mode_thread_.join();
}
joint_velocity_control_mode_thread_ = std::thread(&RobotDriverCoppelia::_start_joint_velocity_control_mode, this);
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::[RobotDriverCoppelia]::connect::Connected to Vrep");
}
void RobotDriverCoppelia::disconnect(){
vi_->disconnect_all();
}
void RobotDriverCoppelia::_start_joint_velocity_control_mirror_thread()
{
finish_motion_ = false;
if (joint_velocity_control_mode_thread_.joinable())
void RobotDriverCoppelia::initialize(){
if(configuration_.using_real_robot)
{
joint_velocity_control_mode_thread_.join();
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::[RobotDriverCoppelia]::initialize::Waiting for real robot interface to initialize...");
rclcpp::spin_some(node_sptr_);
int count = 0;
while (!real_robot_interface_->is_enabled(sas::RobotDriver::Functionality::PositionControl)) {
rclcpp::spin_some(node_sptr_);
// std::cout<<"Waiting for real robot interface to initialize..."<<std::endl;
std::this_thread::sleep_for(std::chrono::milliseconds(100));
rclcpp::spin_some(node_sptr_);
count++;
if(count > REAL_ROBOT_INTERFACE_INIT_TIMEOUT_COUNT){
RCLCPP_ERROR_STREAM(node_sptr_->get_logger(), "::[RobotDriverCoppelia]::initialize::Real robot interface not initialized. Exiting on TIMEOUT...");
throw std::runtime_error("[" + std::string(node_sptr_->get_name()) +"]::[RobotDriverCoppelia]::initialize::Real robot interface not initialized.");
}
if (joint_velocity_control_mirror_mode_thread_.joinable())
if(!rclcpp::ok()) {
RCLCPP_WARN_STREAM(node_sptr_->get_logger(), "::[RobotDriverCoppelia]::initialize::ROS shutdown received. Exiting...");
throw std::runtime_error("[" + std::string(node_sptr_->get_name()) +"]::[RobotDriverCoppelia]::initialize::ROS shutdown received, not OK.");
}
}
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::[RobotDriverCoppelia]::initialize::Real robot interface initialized.");
joint_limits_ = real_robot_interface_->get_joint_limits();
_update_vrep_position(real_robot_interface_->get_joint_positions(), true);
}else{
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::[RobotDriverCoppelia]::initialize::Simulation mode.");
// initialization information for robot driver provider
/**
* TODO: check for making sure real robot is not actually connected
*/
auto current_joint_positions = vi_->get_joint_positions(configuration_.vrep_joint_names);
VectorXd current_joint_velocity;
if(robot_mode_ == ControlMode::Velocity)
{current_joint_velocity = VectorXd::Zero(current_joint_positions.size());}
robot_provider_->send_joint_states(current_joint_positions, current_joint_velocity, VectorXd());
robot_provider_->send_joint_limits(joint_limits_);
// start velocity control simulation thread if needed
if(robot_mode_ == ControlMode::Velocity)
{
joint_velocity_control_mirror_mode_thread_.join();
simulated_joint_positions_ = current_joint_positions;
simulated_joint_velocities_ = current_joint_velocity;
start_simulation_thread();
}
joint_velocity_control_mirror_mode_thread_ = std::thread(&RobotDriverCoppelia::_start_joint_velocity_control_mirror_mode, this);
}
}
void RobotDriverCoppelia::deinitialize(){
// nothing to do
}
void RobotDriverCoppelia::_start_joint_velocity_control_mirror_mode()
{
void RobotDriverCoppelia::start_simulation_thread(){ // thread entry point
if(simulation_thread_started_){
throw std::runtime_error("[RobotDriverCoppelia]::start_simulation_thread::Simulation thread already started");
}
if(velocity_control_simulation_thread_.joinable()){
velocity_control_simulation_thread_.join();
}
velocity_control_simulation_thread_ = std::thread(&RobotDriverCoppelia::_velocity_control_simulation_thread_main, this);
}
void RobotDriverCoppelia::_velocity_control_simulation_thread_main(){
/**
* This thread should not access vrep
*/
simulation_thread_started_ = true;
try{
finish_motion_ = false;
std::cout<<"RobotDriverCoppelia::Waiting for real robot topics..."<<std::endl;
VectorXd q;
while (ros::ok()) {
if (franka1_ros_->is_enabled())
{
q = franka1_ros_->get_joint_positions();
break;
}
ros::spinOnce();
}
std::cout<<"RobotDriverCoppelia::Done!"<<std::endl;
RCLCPP_INFO_STREAM(node_sptr_->get_logger(), "::RobotDriverCoppelia]::[_velocity_control_simulation_thread_main]::Simulation thread started.");
sas::Clock clock = sas::Clock(VIRTUAL_ROBOT_SIMULATION_SAMPLING_TIME_SEC);
double tau = VIRTUAL_ROBOT_SIMULATION_SAMPLING_TIME_SEC;
auto current_joint_positions = simulated_joint_positions_;
clock.init();
while (!(*break_loops_) && rclcpp::ok()) {
VectorXd q_vrep = vi_->get_joint_positions(jointnames_);
VectorXd q_dot_vrep = vi_->get_joint_velocities(jointnames_);
VectorXd forces_vrep = vi_->get_joint_torques(jointnames_);
_update_robot_state(q_vrep, q_dot_vrep, forces_vrep);
desired_joint_positions_ = q_vrep;
while(ros::ok())
{
q = franka1_ros_->get_joint_positions();
if (q.size() == dim_configuration_space_)
{
VectorXd q_vrep = vi_->get_joint_positions(jointnames_);
VectorXd q_dot_vrep = vi_->get_joint_velocities(jointnames_);
VectorXd forces_vrep = vi_->get_joint_torques(jointnames_);
_update_robot_state(q_vrep, q_dot_vrep, forces_vrep);
if (robot_mode_ == std::string("VelocityControl"))
{
vi_->set_joint_target_velocities(jointnames_, gain_*(q-q_vrep));
current_joint_positions += tau * simulated_joint_velocities_; // no dynamic model
// cap joint limit
auto q_min = std::get<0>(joint_limits_);
auto q_max = std::get<1>(joint_limits_);
for (int i = 0; i < current_joint_positions.size(); i++) {
if (current_joint_positions(i) < q_min(i)) {
current_joint_positions(i) = q_min(i);
}
else if (robot_mode_ == std::string("PositionControl"))
{
vi_->set_joint_target_positions(jointnames_, q);
}
if (finish_motion_) {
finish_motion_ = false;
return;
if (current_joint_positions(i) > q_max(i)) {
current_joint_positions(i) = q_max(i);
}
}
simulated_joint_positions_ = current_joint_positions;
clock.update_and_sleep();
}
}catch(std::exception &e){
RCLCPP_ERROR_STREAM(node_sptr_->get_logger(), "::[RobotDriverCoppelia]::[_velocity_control_simulation_thread_main]::Exception::" << e.what());
simulation_thread_started_ = false;
}catch(...){
RCLCPP_ERROR_STREAM(node_sptr_->get_logger(), "::[RobotDriverCoppelia]::[_velocity_control_simulation_thread_main]::Exception::Unknown");
simulation_thread_started_ = false;
}
catch(const std::exception& e)
{
std::cout<<"RobotDriverCoppelia::sas_robot_coppelia_driver::_start_joint_velocity_control_mirror_mode(). Error or exception caught " << e.what()<<std::endl;
}
catch(...)
{
std::cout<<"RobotDriverCoppelia::sas_robot_coppelia_driver::_start_joint_velocity_control_mirror_mode(). Error or exception caught " <<std::endl;
}
break_loops_->store(true);
}
} // sas namespace

View File

@@ -1,134 +0,0 @@
/*
# Copyright (c) 2023 Juan Jose Quiroz Omana
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Juan Jose Quiroz Omana, email: juanjqogm@gmail.com
#
# ################################################################
#
# Contributors:
# 1. Juan Jose Quiroz Omana (juanjqogm@gmail.com)
# - Adapted from sas_robot_driver_denso.cpp
# (https://github.com/SmartArmStack/sas_robot_driver_denso/blob/master/src/sas_robot_driver_denso.cpp)
#
# ################################################################
*/
#pragma once
#include <exception>
#include <tuple>
#include <atomic>
#include <vector>
#include <memory>
#include <dqrobotics/DQ.h>
#include <sas_robot_driver/sas_robot_driver.h>
#include <dqrobotics/interfaces/vrep/DQ_VrepRobot.h>
#include <thread>
#include <sas_robot_driver/sas_robot_driver_interface.h>
using namespace DQ_robotics;
using namespace Eigen;
namespace sas
{
struct RobotDriverCoppeliaConfiguration
{
int thread_sampling_time_nsec;
int port;
std::string ip;
std::vector<std::string> jointnames;
std::string robot_mode;
bool mirror_mode;
std::string real_robot_topic_prefix;
};
class RobotDriverCoppelia: public RobotDriver
{
private:
RobotDriverCoppeliaConfiguration configuration_;
std::string robot_mode_ = std::string("VelocityControl"); // PositionControl
bool mirror_mode_ = false;
double gain_ = 3.0;
std::string real_robot_topic_prefix_;
VectorXd current_joint_positions_;
VectorXd current_joint_velocities_;
VectorXd current_joint_forces_;
VectorXd desired_joint_velocities_;
VectorXd desired_joint_positions_;
std::atomic<bool> finish_motion_;
int dim_configuration_space_;
void _update_robot_state(const VectorXd& q, const VectorXd& q_dot, const VectorXd& forces);
void finish_motion();
void _start_joint_velocity_control_mode();
std::thread joint_velocity_control_mode_thread_;
void _start_joint_velocity_control_thread();
void _start_joint_velocity_control_mirror_mode();
std::thread joint_velocity_control_mirror_mode_thread_;
void _start_joint_velocity_control_mirror_thread();
std::shared_ptr<sas::RobotDriverInterface> franka1_ros_;
protected:
std::shared_ptr<DQ_VrepInterface> vi_;
std::vector<std::string> jointnames_;
public:
RobotDriverCoppelia(const RobotDriverCoppelia&)=delete;
RobotDriverCoppelia()=delete;
~RobotDriverCoppelia();
RobotDriverCoppelia(const RobotDriverCoppeliaConfiguration& configuration, std::atomic_bool* break_loops);
VectorXd get_joint_positions() override;
void set_target_joint_positions(const VectorXd& desired_joint_positions_rad) override;
VectorXd get_joint_velocities() override;
void set_target_joint_velocities(const VectorXd& desired_joint_velocities) override;
VectorXd get_joint_forces() override;
void connect() override;
void disconnect() override;
void initialize() override;
void deinitialize() override;
};
}

View File

@@ -1,63 +0,0 @@
/*
# Copyright (c) 2023 Juan Jose Quiroz Omana
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Juan Jose Quiroz Omana, email: juanjqogm@gmail.com
#
# ################################################################
#
# Contributors:
# 1. Quenitin Lin
#
# ################################################################
*/
#include "sas_robot_dynamic_provider.h"
using namespace sas;
RobotDynamicProvider::RobotDynamicProvider(ros::NodeHandle &nodehandle, const std::string &node_prefix):
RobotDynamicProvider(nodehandle, nodehandle, node_prefix)
{
//Delegated
}
RobotDynamicProvider::RobotDynamicProvider(ros::NodeHandle &publisher_nodehandle, ros::NodeHandle &subscriber_nodehandle, const std::string &node_prefix):
node_prefix_(node_prefix)
{
ROS_INFO_STREAM(ros::this_node::getName() + "::Initializing RobotDynamicProvider with prefix " + node_prefix);
publisher_cartesian_stiffness_ = publisher_nodehandle.advertise<geometry_msgs::WrenchStamped>(node_prefix + "/get/cartesian_stiffness", 1);
publisher_stiffness_pose_ = publisher_nodehandle.advertise<geometry_msgs::PoseStamped>(node_prefix + "/get/stiffness_pose", 1);
}
void RobotDynamicProvider::publish_stiffness(const DQ& base_to_stiffness, const Vector3d& force, const Vector3d& torque) const
{
publisher_stiffness_pose_.publish(dq_to_geometry_msgs_pose_stamped(base_to_stiffness));
geometry_msgs::WrenchStamped msg;
msg.header.stamp = ros::Time::now();
msg.wrench.force.x = force(0);
msg.wrench.force.y = force(1);
msg.wrench.force.z = force(2);
msg.wrench.torque.x = torque(0);
msg.wrench.torque.y = torque(1);
msg.wrench.torque.z = torque(2);
publisher_cartesian_stiffness_.publish(msg);
}

View File

@@ -1,60 +0,0 @@
#pragma once
/*
# Copyright (c) 2023 Juan Jose Quiroz Omana
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Juan Jose Quiroz Omana, email: juanjqogm@gmail.com
#
# ################################################################
#
# Contributors:
# 1. Quenitin Lin
#
# ################################################################
*/
#include <ros/ros.h>
#include <ros/node_handle.h>
#include <sas_common/sas_common.h>
#include <sas_conversions/sas_conversions.h>
#include <geometry_msgs/WrenchStamped.h>
#include <geometry_msgs/PoseStamped.h>
#include <dqrobotics/DQ.h>
namespace sas {
using namespace DQ_robotics;
class RobotDynamicProvider {
private:
std::string node_prefix_;
ros::Publisher publisher_cartesian_stiffness_;
ros::Publisher publisher_stiffness_pose_;
public:
RobotDynamicProvider(ros::NodeHandle& nodehandle, const std::string& node_prefix=ros::this_node::getName());
RobotDynamicProvider(ros::NodeHandle& publisher_nodehandle, ros::NodeHandle& subscriber_nodehandle, const std::string& node_prefix=ros::this_node::getName());
void publish_stiffness(const DQ& base_to_stiffness, const Vector3d& force, const Vector3d& torque) const;
};
} // namespace sas

View File

@@ -28,7 +28,7 @@
#
# ################################################################
*/
#include "generator/custom_motion_generation.h"
#include <sas_robot_driver_franka/generator/custom_motion_generation.h>
/**
* @brief CustomMotionGeneration::CustomMotionGeneration

View File

@@ -1,6 +1,6 @@
// Copyright (c) 2017 Franka Emika GmbH
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
#include "generator/motion_generator.h"
#include <sas_robot_driver_franka/generator/motion_generator.h>
#include <algorithm>
#include <array>
#include <cmath>

View File

@@ -1,4 +1,4 @@
#include "generator/quadratic_program_motion_generator.h"
#include <sas_robot_driver_franka/generator/quadratic_program_motion_generator.h>
QuadraticProgramMotionGenerator::QuadraticProgramMotionGenerator(const double &speed_factor,

View File

@@ -0,0 +1,318 @@
/*
# Copyright (c) 2023 Juan Jose Quiroz Omana
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Juan Jose Quiroz Omana, email: juanjqogm@gmail.com
#
# ################################################################
#
# Contributors:
# 1. Quenitin Lin
#
# ################################################################
*/
#include <sas_robot_driver_franka/interfaces/qros_effector_driver_franka_hand.hpp>
#include <franka/exception.h>
using namespace std::placeholders;
using namespace sas_robot_driver_franka_interfaces;
namespace qros
{
//const static int SLAVE_MODE_JOINT_CONTROL;
//const static int SLAVE_MODE_END_EFFECTOR_CONTROL;
EffectorDriverFrankaHand::~EffectorDriverFrankaHand()
{
if (_is_connected())
{
disconnect();
}
}
EffectorDriverFrankaHand::EffectorDriverFrankaHand(
const std::string& driver_node_prefix,
const EffectorDriverFrankaHandConfiguration& configuration,
std::shared_ptr<Node> node,
std::atomic_bool* break_loops):
driver_node_prefix_(driver_node_prefix),
configuration_(configuration),
node_(node),
break_loops_(break_loops)
{
gripper_sptr_ = nullptr;
grasp_srv_ = node->create_service<srv::Grasp>(driver_node_prefix_ + "/grasp",
std::bind(&EffectorDriverFrankaHand::_grasp_srv_callback, this, _1, _2));
move_srv_ = node->create_service<srv::Move>(driver_node_prefix_ + "/move",
std::bind(&EffectorDriverFrankaHand::_move_srv_callback, this, _1, _2));
gripper_status_publisher_ = node->create_publisher<msg::GripperState>(
driver_node_prefix_ + "/gripper_status", 1);
}
bool EffectorDriverFrankaHand::_is_connected() const
{
#ifdef IN_TESTING
return true;
#endif
if (gripper_sptr_ == nullptr) return false;
if (!gripper_sptr_) return false;
else return true;
}
void EffectorDriverFrankaHand::start_control_loop() {
sas::Clock clock = sas::Clock(configuration_.thread_sampeling_time_s);
clock.init();
RCLCPP_INFO_STREAM(node_->get_logger(),"[EffectorDriverFrankaHand]::start_control_loop::Starting control loop.");
RCLCPP_WARN_STREAM(node_->get_logger(),"[EffectorDriverFrankaHand]::Gripper READY.");
while (!(*break_loops_))
{
if (!_is_connected()) throw std::runtime_error("[" + std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::start_control_loop::Robot is not connected.");
if (!status_loop_running_)
{
RCLCPP_WARN_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_is_connected::Status loop is not running.");
break_loops_->store(true);
break;
}
clock.update_and_sleep();
spin_some(node_);
}
RCLCPP_INFO_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::start_control_loop::Exiting control loop.");
}
void EffectorDriverFrankaHand::connect()
{
#ifdef IN_TESTING
RCLCPP_WARN_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::connect::In testing mode. to DUMMY");
return;
#endif
gripper_sptr_ = std::make_shared<franka::Gripper>(configuration_.robot_ip);
if (!_is_connected()) throw std::runtime_error(
"[" + std::string(node_->get_name())+
"]::[EffectorDriverFrankaHand]::connect::Could not connect to the robot.");
}
void EffectorDriverFrankaHand::disconnect() noexcept
{
#ifdef IN_TESTING
RCLCPP_WARN_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::disconnect::In testing mode. from DUMMY");
return;
#endif
RCLCPP_WARN_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::disconnecting...");
gripper_sptr_->~Gripper();
gripper_sptr_ = nullptr;
}
/**
* @brief robot_driver_franka::gripper_homing
*/
void EffectorDriverFrankaHand::gripper_homing()
{
#ifdef IN_TESTING
RCLCPP_WARN_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::gripper_homing::In testing mode.");
return;
#endif
if (!_is_connected()) throw std::runtime_error(
"[" + std::string(node_->get_name())+ "]::[EffectorDriverFrankaHand]::gripper_homing::Robot is not connected.");
auto ret = gripper_sptr_->homing();
if (!ret)
{
throw std::runtime_error("[" + std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::gripper_homing::Failed to home the gripper.");
}
RCLCPP_INFO_STREAM(node_->get_logger(),"[EffectorDriverFrankaHand]::gripper_homing::Gripper homed.");
}
void EffectorDriverFrankaHand::initialize()
{
if (!_is_connected()) throw std::runtime_error(
"[" + std::string(node_->get_name())+ "]::[EffectorDriverFrankaHand]::initialize::Robot is not connected.");
gripper_homing();
// start gripper status loop
status_loop_thread_ = std::thread(&EffectorDriverFrankaHand::_gripper_status_loop, this);
// check status loop with timeout
auto time_now = std::chrono::system_clock::now();
auto time_out = time_now + std::chrono::seconds(5);
while (!status_loop_running_)
{
if (std::chrono::system_clock::now() > time_out){throw std::runtime_error("[" + std::string(node_->get_name()) + "]::[EffectorDriverFrankaHand]::initialize::Could not start status loop.");}
std::this_thread::sleep_for(std::chrono::milliseconds(100));
}
}
void EffectorDriverFrankaHand::deinitialize()
{
#ifdef IN_TESTING
RCLCPP_WARN_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::deinitialize::In testing mode.");
return;
#endif
if (_is_connected())
{
franka::GripperState gripper_state = gripper_sptr_->readOnce();
if (gripper_state.is_grasped)
{
gripper_sptr_->stop();
}
}
}
bool EffectorDriverFrankaHand::_grasp_srv_callback(const std::shared_ptr<srv::Grasp::Request> req, std::shared_ptr<srv::Grasp::Response> res)
{
RCLCPP_DEBUG_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_grasp_srv_callback::Grasping...");
auto force = req->force;
auto speed = req->speed;
auto epsilon_inner = req->epsilon_inner;
auto epsilon_outer = req->epsilon_outer;
if (force <= 0.0) force = configuration_.default_force;
if (speed <= 0.0) speed = configuration_.default_speed;
if (epsilon_inner <= 0.0) epsilon_inner = configuration_.default_epsilon_inner;
if (epsilon_outer <= 0.0) epsilon_outer = configuration_.default_epsilon_outer;
RCLCPP_DEBUG_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_grasp_srv_callback::Width: " + std::to_string(req->width));
RCLCPP_DEBUG_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_grasp_srv_callback::force: " + std::to_string(force) + " speed: " + std::to_string(speed));
bool ret = false;
bool function_ret = true;
gripper_in_use_.lock();
#ifdef IN_TESTING
ret = true;
std::this_thread::sleep_for(std::chrono::milliseconds(2000));
#else
try
{
ret = gripper_sptr_->grasp(req->width, speed, force, epsilon_inner, epsilon_outer);
}catch(franka::CommandException& e)
{
RCLCPP_ERROR_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_grasp_srv_callback::CommandException::" + e.what());
function_ret = false;
}catch(franka::NetworkException& e)
{
RCLCPP_ERROR_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_grasp_srv_callback::NetworkException::" + e.what());
function_ret = false;
}
#endif
gripper_in_use_.unlock();
res->set__success(ret);
return function_ret;
}
bool EffectorDriverFrankaHand::_move_srv_callback(const std::shared_ptr<srv::Move::Request> req, std::shared_ptr<srv::Move::Response> res)
{
RCLCPP_DEBUG_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_move_srv_callback::Moving...");
auto speed = req->speed;
if (speed <= 0.0) speed = configuration_.default_speed;
RCLCPP_DEBUG_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_move_srv_callback::Speed: " + std::to_string(speed) + " Width: " + std::to_string(req->width));
bool ret = false;
bool function_ret = true;
gripper_in_use_.lock();
#ifdef IN_TESTING
ret = true;
std::this_thread::sleep_for(std::chrono::milliseconds(2000));
#else
try
{
ret = gripper_sptr_->move(req->width, speed);
}catch(franka::CommandException& e)
{
RCLCPP_ERROR_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_move_srv_callback::CommandException::" + e.what());
function_ret = false;
}catch(franka::NetworkException& e)
{
RCLCPP_ERROR_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_move_srv_callback::NetworkException::" + e.what());
function_ret = false;
}
#endif
gripper_in_use_.unlock();
res->set__success(ret);
return function_ret;
}
void EffectorDriverFrankaHand::_gripper_status_loop()
{
sas::Clock clock = sas::Clock(configuration_.thread_sampeling_time_s);
RCLCPP_INFO_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_gripper_status_loop::Starting status loop.");
clock.init();
try
{
status_loop_running_ = true;
while (status_loop_running_)
{
#ifdef BLOCK_READ_IN_USED
bool should_unlock = false;
#endif
if (!_is_connected()) throw std::runtime_error(
"[" + std::string(node_->get_name())+
"]::[EffectorDriverFrankaHand]::_gripper_status_loop::Robot is not connected.");
try
{
#ifdef IN_TESTING
RCLCPP_WARN_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_gripper_status_loop::In testing mode.");
throw std::runtime_error("[" + std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_gripper_status_loop::In testing mode.");
#endif
#ifdef BLOCK_READ_IN_USED
gripper_in_use_.lock();
should_unlock = true;
#endif
franka::GripperState gripper_state = gripper_sptr_->readOnce();
#ifdef BLOCK_READ_IN_USED
gripper_in_use_.unlock();
#endif
msg::GripperState msg;
msg.set__width(static_cast<float>(gripper_state.width));
msg.set__max_width(static_cast<float>(gripper_state.max_width));
msg.set__is_grasped(gripper_state.is_grasped);
msg.set__temperature(gripper_state.temperature);
msg.set__duration_ms(gripper_state.time.toMSec());
gripper_status_publisher_->publish(msg);
}
catch (...)
{
#ifdef BLOCK_READ_IN_USED
if (should_unlock) gripper_in_use_.unlock();
#endif
RCLCPP_INFO_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_gripper_status_loop::Could not read gripper state. Unavailable.");
msg::GripperState msg;
msg.width = 0.0;
gripper_status_publisher_->publish(msg);
}
clock.update_and_sleep();
}
status_loop_running_ = false;
}
catch (std::exception& e)
{
RCLCPP_ERROR_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_gripper_status_loop::Exception::" + e.
what());
status_loop_running_ = false;
}
catch (...)
{
RCLCPP_ERROR_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+
"]::[EffectorDriverFrankaHand]::_gripper_status_loop::Exception::Unknown exception.");
status_loop_running_ = false;
}
RCLCPP_INFO_STREAM(node_->get_logger(),"["+ std::string(node_->get_name())+"]::[EffectorDriverFrankaHand]::_gripper_status_loop::Exiting status loop.");
}
} // qros

View File

@@ -1,4 +1,33 @@
#include "robot_interface_hand.h"
/*
# Copyright (c) 2023 Juan Jose Quiroz Omana
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Juan Jose Quiroz Omana, email: juanjqogm@gmail.com
#
# ################################################################
#
# Contributors:
# 1. Quenitin Lin
#
# ################################################################
*/
#include "sas_robot_driver_franka/robot_interface_hand.hpp"

View File

@@ -1,152 +0,0 @@
/*
# Copyright (c) 2023 Juan Jose Quiroz Omana
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Juan Jose Quiroz Omana, email: juanjqogm@gmail.com
#
# ################################################################
#
# Contributors:
# 1. Quenitin Lin
#
# ################################################################
*/
#include "sas_robot_driver_franka_hand.h"
namespace sas {
//const static int SLAVE_MODE_JOINT_CONTROL;
//const static int SLAVE_MODE_END_EFFECTOR_CONTROL;
RobotDriverFrankaHand::~RobotDriverFrankaHand()
{
if(_is_connected())
{
disconnect();
}
}
RobotDriverFrankaHand::RobotDriverFrankaHand(
const RobotDriverFrankaHandConfiguration& configuration,
const RobotDriverROSConfiguration& ros_configuration,
std::atomic_bool* break_loops):
configuration_(configuration), ros_configuration_(ros_configuration), break_loops_(break_loops)
{
gripper_sptr_ = nullptr;
}
bool RobotDriverFrankaHand::_is_connected() const
{
if(gripper_sptr_ == nullptr) return false;
if(!gripper_sptr_) return false;
else return true;
}
VectorXd RobotDriverFrankaHand::get_joint_positions()
{
return joint_positions_;
}
void RobotDriverFrankaHand::set_target_joint_positions(const VectorXd& desired_joint_positions_rad)
{
}
VectorXd RobotDriverFrankaHand::get_joint_velocities()
{
return VectorXd::Zero(1);
}
void RobotDriverFrankaHand::set_target_joint_velocities(const VectorXd& desired_joint_velocities)
{
}
VectorXd RobotDriverFrankaHand::get_joint_forces()
{
return VectorXd::Zero(1);
}
void RobotDriverFrankaHand::start_control_loop()
{
Clock clock = Clock(ros_configuration_.thread_sampling_time_nsec);
clock.init();
ROS_INFO_STREAM("["+ ros::this_node::getName()+"]::[RobotDriverFrankaHand]::start_control_loop::Starting control loop.");
while(!(*break_loops_))
{
if(!_is_connected()) throw std::runtime_error("["+ ros::this_node::getName()+"]::[RobotDriverFrankaHand]::start_control_loop::Robot is not connected.");
clock.update_and_sleep();
}
ROS_INFO_STREAM("["+ ros::this_node::getName()+"]::[RobotDriverFrankaHand]::start_control_loop::Exiting control loop.");
}
void RobotDriverFrankaHand::connect()
{
gripper_sptr_ = std::make_shared<franka::Gripper>(configuration_.robot_ip);
if(!_is_connected()) throw std::runtime_error("["+ ros::this_node::getName()+"]::[RobotDriverFrankaHand]::connect::Could not connect to the robot.");
}
void RobotDriverFrankaHand::disconnect() noexcept
{
ROS_WARN_STREAM("["+ ros::this_node::getName()+"]::[RobotDriverFrankaHand]::disconnecting...");
gripper_sptr_->~Gripper();
gripper_sptr_ = nullptr;
}
/**
* @brief robot_driver_franka::gripper_homing
*/
void RobotDriverFrankaHand::gripper_homing()
{
if(!_is_connected()) throw std::runtime_error("["+ ros::this_node::getName()+"]::[RobotDriverFrankaHand]::gripper_homing::Robot is not connected.");
auto ret = gripper_sptr_->homing();
if(!ret)
{
throw std::runtime_error("["+ ros::this_node::getName()+"]::[RobotDriverFrankaHand]::gripper_homing::Failed to home the gripper.");
}
ROS_INFO_STREAM("["+ ros::this_node::getName()+"]::[RobotDriverFrankaHand]::gripper_homing::Gripper homed.");
}
void RobotDriverFrankaHand::initialize()
{
if(!_is_connected()) throw std::runtime_error("["+ ros::this_node::getName()+"]::[RobotDriverFrankaHand]::initialize::Robot is not connected.");
gripper_homing();
}
void RobotDriverFrankaHand::deinitialize()
{
if(_is_connected())
{
franka::GripperState gripper_state = gripper_sptr_->readOnce();
if(gripper_state.is_grasped)
{
gripper_sptr_->stop();
}
}
}
} // sas

View File

@@ -1,117 +0,0 @@
#pragma once
/*
# Copyright (c) 2023 Juan Jose Quiroz Omana
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Juan Jose Quiroz Omana, email: juanjqogm@gmail.com
#
# ################################################################
#
# Contributors:
# 1. Quenitin Lin
#
# ################################################################
*/
#include <exception>
#include <tuple>
#include <atomic>
#include <vector>
#include <memory>
#include <franka/robot.h>
#include <franka/gripper.h>
// #include <thread>
#include <dqrobotics/DQ.h>
#include <sas_robot_driver/sas_robot_driver.h>
#include <sas_robot_driver/sas_robot_driver_ros.h>
#include <sas_clock/sas_clock.h>
#include <ros/common.h>
using namespace DQ_robotics;
using namespace Eigen;
namespace sas {
struct RobotDriverFrankaHandConfiguration
{
std::string robot_ip;
};
class RobotDriverFrankaHand{
private:
RobotDriverFrankaHandConfiguration configuration_;
RobotDriverROSConfiguration ros_configuration_;
std::shared_ptr<franka::Gripper> gripper_sptr_;
//Joint positions
VectorXd joint_positions_;
//VectorXd joint_velocities_;
//VectorXd end_effector_pose_;
// std::thread control_loop_thread_;
std::atomic_bool* break_loops_;
bool _is_connected() const;
public:
//const static int SLAVE_MODE_JOINT_CONTROL;
//const static int SLAVE_MODE_END_EFFECTOR_CONTROL;
RobotDriverFrankaHand(const RobotDriverFrankaHand&)=delete;
RobotDriverFrankaHand()=delete;
~RobotDriverFrankaHand();
RobotDriverFrankaHand(
const RobotDriverFrankaHandConfiguration& configuration,
const RobotDriverROSConfiguration& ros_configuration,
std::atomic_bool* break_loops);
void start_control_loop();
VectorXd get_joint_positions();
void set_target_joint_positions(const VectorXd& desired_joint_positions_rad);
VectorXd get_joint_velocities();
void set_target_joint_velocities(const VectorXd& desired_joint_velocities);
VectorXd get_joint_forces();
void gripper_homing();
void connect() ;
void disconnect() noexcept;
void initialize() ;
void deinitialize() ;
//bool set_end_effector_pose_dq(const DQ& pose);
//DQ get_end_effector_pose_dq();
};
} // sas

View File

@@ -30,10 +30,7 @@
*/
#include "robot_interface_franka.h"
#include <ros/this_node.h>
#include <rosconsole/macros_generated.h>
#include <sas_robot_driver_franka/interfaces/robot_interface_franka.hpp>
/**
@@ -313,6 +310,7 @@ void RobotInterfaceFranka::initialize()
initialize_flag_ = true;
// initialize and set the robot to default behavior (collision behavior, impedance, etc)
// robot_sptr_->setDefaultBehavior();
setDefaultBehavior(*robot_sptr_);
robot_sptr_->setCollisionBehavior(
franka_configuration_.lower_torque_threshold,
@@ -365,7 +363,7 @@ void RobotInterfaceFranka::_update_robot_state(const franka::RobotState &robot_s
current_joint_forces_array_ = robot_state.tau_J;
current_joint_forces_ = Eigen::Map<VectorXd>(current_joint_forces_array_.data(), 7);
current_stiffness_force_torque_array_ = robot_state.O_F_ext_hat_K;
current_stiffness_force_torque_array_ = robot_state.K_F_ext_hat_K;
current_stiffness_force_[0] = current_stiffness_force_torque_array_[0];
current_stiffness_force_[1] = current_stiffness_force_torque_array_[1];
current_stiffness_force_[2] = current_stiffness_force_torque_array_[2];
@@ -718,6 +716,7 @@ DQ RobotInterfaceFranka::get_stiffness_pose() {
const auto base_2_ee = homgenious_tf_to_DQ(current_effeector_pose_);
const auto ee_2_k = homgenious_tf_to_DQ(current_stiffness_pose_);
return base_2_ee * ee_2_k;
// return base_2_k;
}
/**

View File

@@ -31,18 +31,21 @@
*/
#include "../../include/sas_robot_driver_franka.h"
#include "sas_clock/sas_clock.h"
#include <sas_robot_driver_franka/sas_robot_driver_franka.hpp>
#include <sas_core/sas_clock.hpp>
#include <dqrobotics/utils/DQ_Math.h>
#include <ros/this_node.h>
#include <rosconsole/macros_generated.h>
namespace sas
{
RobotDriverFranka::RobotDriverFranka(RobotDynamicProvider* robot_dynamic_provider, const RobotDriverFrankaConfiguration &configuration, std::atomic_bool *break_loops):
RobotDriverFranka::RobotDriverFranka(
const std::shared_ptr<Node> &node,
const std::shared_ptr<qros::RobotDynamicsServer> &robot_dynamic_provider, const RobotDriverFrankaConfiguration &configuration, std::atomic_bool *break_loops
):
RobotDriver(break_loops),
node_(node),
configuration_(configuration),
robot_dynamic_provider_(robot_dynamic_provider),
robot_dynamic_provider_sptr_(robot_dynamic_provider),
break_loops_(break_loops)
{
joint_positions_.resize(7);
@@ -52,11 +55,10 @@ namespace sas
//joint_positions_buffer_.resize(8,0);
//end_effector_pose_euler_buffer_.resize(7,0);
//end_effector_pose_homogenous_transformation_buffer_.resize(10,0);
std::cout<<configuration.ip_address<<std::endl;
// std::cout<<configuration.ip_address<<std::endl;
RobotInterfaceFranka::MODE mode = RobotInterfaceFranka::MODE::None;
std::cout<<configuration.mode<<std::endl;
RCLCPP_INFO_STREAM(node_->get_logger(), "Mode: " << configuration_.mode);
if (configuration_.mode == std::string("None"))
{
@@ -90,7 +92,7 @@ namespace sas
Vector3d force, torque;
std::tie(force, torque) = robot_driver_interface_sptr_->get_stiffness_force_torque();
const auto pose = robot_driver_interface_sptr_->get_stiffness_pose();
robot_dynamic_provider_->publish_stiffness(pose, force, torque);
robot_dynamic_provider_sptr_->publish_stiffness(pose, force, torque);
}
@@ -143,9 +145,16 @@ namespace sas
VectorXd RobotDriverFranka::get_joint_positions()
{
if(robot_driver_interface_sptr_->get_err_state()) {
ROS_ERROR_STREAM("["+ros::this_node::getName()+"]::driver interface error on:"+robot_driver_interface_sptr_->get_status_message());
RCLCPP_ERROR_STREAM(node_->get_logger(),
"["+std::string(node_->get_name())+"]::driver interface "
"error on:"+robot_driver_interface_sptr_->get_status_message());
break_loops_->store(true);
}
if(!ok()) {
RCLCPP_WARN_STREAM(node_->get_logger(),
"["+std::string(node_->get_name())+"]::driver interface exit on shotdown signal recieved."
);
}
_update_stiffness_contact_and_pose();
return robot_driver_interface_sptr_->get_joint_positions();
}
@@ -160,7 +169,9 @@ namespace sas
{
robot_driver_interface_sptr_->set_target_joint_positions(desired_joint_positions_rad);
if(robot_driver_interface_sptr_->get_err_state()) {
ROS_ERROR_STREAM("["+ros::this_node::getName()+"]::driver interface error on:"+robot_driver_interface_sptr_->get_status_message());
RCLCPP_ERROR_STREAM(node_->get_logger(),
"["+std::string(node_->get_name())+"]::driver interface "
"error on:"+robot_driver_interface_sptr_->get_status_message());
break_loops_->store(true);
}
}
@@ -185,7 +196,9 @@ namespace sas
desired_joint_velocities_ = desired_joint_velocities;
robot_driver_interface_sptr_->set_target_joint_velocities(desired_joint_velocities);
if(robot_driver_interface_sptr_->get_err_state()) {
ROS_ERROR_STREAM("["+ros::this_node::getName()+"]::driver interface error on:"+robot_driver_interface_sptr_->get_status_message());
RCLCPP_ERROR_STREAM(node_->get_logger(),
"["+std::string(node_->get_name())+"]::driver interface "
"error on:"+robot_driver_interface_sptr_->get_status_message());
break_loops_->store(true);
}
}

View File

@@ -0,0 +1,102 @@
/*
# Copyright (c) 2024 Quenitin Lin
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Quenitin Lin
#
# ################################################################
#
# Contributors:
# 1. Quenitin Lin
#
# ################################################################
*/
#include <memory>
#include <sas_robot_driver_franka/robot_dynamic/qros_robot_dynamics_client.hpp>
using namespace qros;
RobotDynamicsClient::RobotDynamicsClient(const std::shared_ptr<Node> &node, const std::string& topic_prefix):
node_(node), topic_prefix_(topic_prefix == "GET_FROM_NODE"? node->get_name() : topic_prefix),
child_frame_id_(topic_prefix_ + "_stiffness_frame"), parent_frame_id_(topic_prefix_ + "_base"),
last_stiffness_force_(Vector3d::Zero()),
last_stiffness_torque_(Vector3d::Zero()),
last_stiffness_frame_pose_(0)
{
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(node->get_clock());
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
// Strip potential leading slash
if(child_frame_id_.front() == '/'){child_frame_id_ = child_frame_id_.substr(1);}
if(parent_frame_id_.front() == '/'){parent_frame_id_ = parent_frame_id_.substr(1);}
RCLCPP_INFO_STREAM(node_->get_logger(),
"["+ std::string(node_->get_name()) + "]::Initializing RobotDynamicsClient with prefix " + topic_prefix);
subscriber_cartesian_stiffness_ = node_->create_subscription<geometry_msgs::msg::WrenchStamped>(topic_prefix + "/get/cartesian_stiffness", 1,
std::bind(&RobotDynamicsClient::_callback_cartesian_stiffness, this, std::placeholders::_1)
);
}
void RobotDynamicsClient::_callback_cartesian_stiffness(const geometry_msgs::msg::WrenchStamped &msg)
{
last_stiffness_force_(0) = msg.wrench.force.x;
last_stiffness_force_(1) = msg.wrench.force.y;
last_stiffness_force_(2) = msg.wrench.force.z;
last_stiffness_torque_(0) = msg.wrench.torque.x;
last_stiffness_torque_(1) = msg.wrench.torque.y;
last_stiffness_torque_(2) = msg.wrench.torque.z;
try {
const auto transform_stamped = tf_buffer_->lookupTransform( parent_frame_id_, child_frame_id_, tf2::TimePointZero);
last_stiffness_frame_pose_ = _geometry_msgs_transform_to_dq(transform_stamped.transform);
} catch (tf2::TransformException &ex) {
RCLCPP_WARN_STREAM(node_->get_logger(), "["+ std::string(node_->get_name()) + "]::" + ex.what());
}
}
DQ RobotDynamicsClient::_geometry_msgs_transform_to_dq(const geometry_msgs::msg::Transform& transform)
{
const auto t = DQ(0,transform.translation.x,transform.translation.y,transform.translation.z);
const auto r = DQ(transform.rotation.w, transform.rotation.x, transform.rotation.y, transform.rotation.z);
return r + 0.5 * E_ * t * r;
}
VectorXd RobotDynamicsClient::get_stiffness_force()
{
if(!is_enabled()) throw std::runtime_error("[RobotDynamicsClient]::calling get_stiffness_force on uninitialized topic");
return last_stiffness_force_;
}
VectorXd RobotDynamicsClient::get_stiffness_torque()
{
if(!is_enabled()) throw std::runtime_error("[RobotDynamicsClient]::calling get_stiffness_torque on uninitialized topic");
return last_stiffness_torque_;
}
DQ RobotDynamicsClient::get_stiffness_frame_pose()
{
if(!is_enabled()) throw std::runtime_error("[RobotDynamicsClient]::calling get_stiffness_frame_pose on uninitialized Interface");
return last_stiffness_frame_pose_;
}
bool RobotDynamicsClient::is_enabled() const
{
if(last_stiffness_frame_pose_==0) return false;
return true;
}

View File

@@ -0,0 +1,60 @@
/*
# Copyright (c) 2023 Juan Jose Quiroz Omana
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Quenitin Lin
#
# ################################################################
#
# Contributors:
# 1. Quenitin Lin
#
# ################################################################
*/
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>
#include <pybind11/eigen.h>
#include <sas_robot_driver_franka/robot_dynamic/qros_robot_dynamics_client.hpp>
#include <sas_robot_driver_franka/robot_dynamic/qros_robot_dynamics_server.hpp>
namespace py = pybind11;
using RDC = qros::RobotDynamicsClient;
using RDS = qros::RobotDynamicsServer;
PYBIND11_MODULE(_qros_franka_robot_dynamics_py, m)
{
py::class_<RDC>(m, "RobotDynamicsClient")
.def(py::init<const std::shared_ptr<rclcpp::Node>&,const std::string&>())
.def("get_stiffness_force",&RDC::get_stiffness_force)
.def("get_stiffness_torque",&RDC::get_stiffness_torque)
.def("get_stiffness_frame_pose",&RDC::get_stiffness_frame_pose)
.def("is_enabled",&RDC::is_enabled,"Returns true if the RobotDynamicInterface is enabled.")
.def("get_topic_prefix",&RDC::get_topic_prefix);
py::class_<RDS>(m, "RobotDynamicsServer")
.def(py::init<const std::shared_ptr<rclcpp::Node>&,const std::string&>())
.def("publish_stiffness",&RDS::publish_stiffness)
.def("set_world_to_base_tf", &RDS::set_world_to_base_tf)
.def("is_enabled",&RDS::is_enabled,"Returns true if the RobotDynamicProvider is enabled.")
.def("get_topic_prefix",&RDS::get_topic_prefix);
}

View File

@@ -0,0 +1,120 @@
/*
# Copyright (c) 2024 Quenitin Lin
#
# This file is part of sas_robot_driver_franka.
#
# sas_robot_driver_franka is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# sas_robot_driver_franka is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with sas_robot_driver. If not, see <https://www.gnu.org/licenses/>.
#
# ################################################################
#
# Author: Quenitin Lin
#
# ################################################################
#
# Contributors:
# 1. Quenitin Lin
#
# ################################################################
*/
#include <sas_robot_driver_franka/robot_dynamic/qros_robot_dynamics_server.hpp>
using namespace qros;
RobotDynamicsServer::RobotDynamicsServer(const std::shared_ptr<Node> &node, const std::string& topic_prefix):
node_(node), topic_prefix_(topic_prefix == "GET_FROM_NODE"? node->get_name() : topic_prefix),
child_frame_id_(topic_prefix_ + "_stiffness_frame"), parent_frame_id_(topic_prefix_ + "_base"),
tf_broadcaster_(std::make_shared<tf2_ros::TransformBroadcaster>(node_)),
static_base_tf_broadcaster_(std::make_shared<tf2_ros::StaticTransformBroadcaster>(node_)),
world_to_base_tf_(0)
{
// Strip potential leading slash
if(child_frame_id_.front() == '/'){child_frame_id_ = child_frame_id_.substr(1);}
if(parent_frame_id_.front() == '/'){parent_frame_id_ = parent_frame_id_.substr(1);}
RCLCPP_INFO_STREAM(node_->get_logger(),
"["+ std::string(node_->get_name()) + "]::Initializing RobotDynamicsServer with prefix " + topic_prefix);
publisher_cartesian_stiffness_ = node_->create_publisher<geometry_msgs::msg::WrenchStamped>(topic_prefix + "/get/cartesian_stiffness", 1);
}
geometry_msgs::msg::Transform RobotDynamicsServer::_dq_to_geometry_msgs_transform(const DQ& pose)
{
geometry_msgs::msg::Transform tf_msg;
const auto t = translation(pose);
const auto r = rotation(pose);
tf_msg.translation.x = t.q(1);
tf_msg.translation.y = t.q(2);
tf_msg.translation.z = t.q(3);
tf_msg.rotation.w = r.q(0);
tf_msg.rotation.x = r.q(1);
tf_msg.rotation.y = r.q(2);
tf_msg.rotation.z = r.q(3);
return tf_msg;
}
void RobotDynamicsServer::set_world_to_base_tf(const DQ& world_to_base_tf)
{
if(world_to_base_tf_==0)
{
world_to_base_tf_ = world_to_base_tf;
_publish_base_static_tf();
}else
{
throw std::runtime_error("["+ std::string(node_->get_name()) + "]::[RobotDynamicsServer]::The world to base transform has already been set");
}
}
void RobotDynamicsServer::_publish_base_static_tf()
{
geometry_msgs::msg::TransformStamped base_tf;
base_tf.set__transform(_dq_to_geometry_msgs_transform(world_to_base_tf_));
std_msgs::msg::Header header;
header.set__stamp(node_->now());
header.set__frame_id(WORLD_FRAME_ID);
base_tf.set__header(header);
base_tf.set__child_frame_id(parent_frame_id_);
static_base_tf_broadcaster_->sendTransform(base_tf);
}
void RobotDynamicsServer::publish_stiffness(const DQ& base_to_stiffness, const Vector3d& force, const Vector3d& torque)
{
std_msgs::msg::Header header;
header.set__stamp(node_->now());
geometry_msgs::msg::WrenchStamped msg;
msg.set__header(header);
msg.header.set__frame_id(child_frame_id_);
msg.wrench.force.set__x(force(0));
msg.wrench.force.set__y(force(1));
msg.wrench.force.set__z(force(2));
msg.wrench.torque.set__x(torque(0));
msg.wrench.torque.set__y(torque(1));
msg.wrench.torque.set__z(torque(2));
publisher_cartesian_stiffness_->publish(msg);
if(seq_ % REDUCE_TF_PUBLISH_RATE == 0)
{
header.set__frame_id(parent_frame_id_);
geometry_msgs::msg::TransformStamped tf_msg;
tf_msg.set__transform(_dq_to_geometry_msgs_transform(base_to_stiffness));
tf_msg.set__header(header);
tf_msg.set__child_frame_id(child_frame_id_);
tf_broadcaster_->sendTransform(tf_msg);
}
}
bool RobotDynamicsServer::is_enabled() const
{
return true; //Always enabled
}

View File

@@ -26,6 +26,9 @@
# 1. Juan Jose Quiroz Omana (juanjqogm@gmail.com)
# - Adapted from sas_robot_driver_denso_node.cpp
# (https://github.com/SmartArmStack/sas_robot_driver_denso/blob/master/src/sas_robot_driver_denso_node.cpp)
# 2. Quentin Lin (qlin1806@g.ecc.u-tokyo.ac.jp)
# - Adapted for simplify operation
# - porting to ROS2
#
# ################################################################
*/
@@ -36,10 +39,9 @@
#include <exception>
#include <dqrobotics/utils/DQ_Math.h>
//#include <dqrobotics/interfaces/json11/DQ_JsonReader.h>
#include <sas_common/sas_common.h>
#include <sas_conversions/eigen3_std_conversions.h>
#include <sas_robot_driver/sas_robot_driver_ros.h>
#include "coppelia/sas_robot_driver_coppelia.h"
#include <sas_common/sas_common.hpp>
#include <sas_conversions/eigen3_std_conversions.hpp>
#include <sas_robot_driver_franka/coppelia/sas_robot_driver_coppelia.hpp>
/*********************************************
* SIGNAL HANDLER
@@ -52,52 +54,51 @@ void sig_int_handler(int)
}
int main(int argc, char **argv)
{
if(signal(SIGINT, sig_int_handler) == SIG_ERR)
{
throw std::runtime_error(ros::this_node::getName() + "::Error setting the signal int handler.");
throw std::runtime_error("Error setting the signal int handler.");
}
ros::init(argc, argv, "sas_robot_driver_coppelia_node", ros::init_options::NoSigintHandler);
ROS_WARN("=====================================================================");
ROS_WARN("----------------------Juan Jose Quiroz Omana------------------------");
ROS_WARN("=====================================================================");
ROS_INFO_STREAM(ros::this_node::getName()+"::Loading parameters from parameter server.");
rclcpp::init(argc,argv,rclcpp::InitOptions(),rclcpp::SignalHandlerOptions::None);
auto context = rclcpp::contexts::get_global_default_context();
auto node = std::make_shared<rclcpp::Node>("sas_robot_driver_franka_coppelia_node");
const auto node_name = std::string(node->get_name());
RCLCPP_WARN(node->get_logger(),"=====================================================================");
RCLCPP_WARN(node->get_logger(),"-----------------Adapted by Quentin Lin ------------------------");
RCLCPP_WARN(node->get_logger(),"=====================================================================");
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),":Loading parameters from parameter server.");
ros::NodeHandle nh;
sas::RobotDriverCoppeliaConfiguration robot_driver_coppelia_configuration;
sas::get_ros_param(nh,"/robot_ip_address",robot_driver_coppelia_configuration.ip);
sas::get_ros_param(nh,"/robot_mode", robot_driver_coppelia_configuration.robot_mode);
sas::get_ros_param(nh,"/vrep_port", robot_driver_coppelia_configuration.port);
sas::get_ros_param(nh,"/vrep_robot_joint_names", robot_driver_coppelia_configuration.jointnames);
sas::get_ros_param(nh,"/mirror_mode", robot_driver_coppelia_configuration.mirror_mode);
sas::get_ros_param(nh, "/real_robot_topic_prefix", robot_driver_coppelia_configuration.real_robot_topic_prefix);
sas::RobotDriverROSConfiguration robot_driver_ros_configuration;
sas::get_ros_param(nh,"/thread_sampling_time_nsec",robot_driver_ros_configuration.thread_sampling_time_nsec);
sas::get_ros_param(nh,"/q_min",robot_driver_ros_configuration.q_min);
sas::get_ros_param(nh,"/q_max",robot_driver_ros_configuration.q_max);
robot_driver_ros_configuration.robot_driver_provider_prefix = ros::this_node::getName();
qros::RobotDriverCoppeliaConfiguration robot_driver_coppelia_configuration;
sas::get_ros_parameter(node,"thread_sampling_time_sec",robot_driver_coppelia_configuration.thread_sampling_time_sec);
sas::get_ros_parameter(node,"vrep_ip",robot_driver_coppelia_configuration.vrep_ip);
sas::get_ros_parameter(node,"vrep_port",robot_driver_coppelia_configuration.vrep_port);
sas::get_ros_parameter(node,"vrep_joint_names", robot_driver_coppelia_configuration.vrep_joint_names);
sas::get_ros_parameter(node,"vrep_dynamically_enabled", robot_driver_coppelia_configuration.vrep_dynamically_enabled);
sas::get_ros_parameter(node,"robot_mode", robot_driver_coppelia_configuration.robot_mode);
sas::get_ros_parameter(node,"using_real_robot", robot_driver_coppelia_configuration.using_real_robot);
sas::get_ros_parameter(node,"robot_topic_prefix", robot_driver_coppelia_configuration.robot_topic_prefix);
sas::get_ros_parameter(node,"robot_parameter_file_path", robot_driver_coppelia_configuration.robot_parameter_file_path);
try
{
ROS_INFO_STREAM(ros::this_node::getName()+"::Instantiating Coppelia robot.");
sas::RobotDriverCoppelia robot_driver_coppelia(robot_driver_coppelia_configuration,
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),"::Instantiating Coppelia robot mirror.");
qros::RobotDriverCoppelia robot_driver_coppelia(node, robot_driver_coppelia_configuration,
&kill_this_process);
ROS_INFO_STREAM(ros::this_node::getName()+"::Instantiating RobotDriverROS.");
sas::RobotDriverROS robot_driver_ros(nh,
&robot_driver_coppelia,
robot_driver_ros_configuration,
&kill_this_process);
robot_driver_ros.control_loop();
return robot_driver_coppelia.start_control_loop();
}
catch (const std::exception& e)
{
ROS_ERROR_STREAM(ros::this_node::getName() + "::Exception::" + e.what());
kill_this_process = true;
RCLCPP_ERROR_STREAM_ONCE(node->get_logger(),"["+node_name+"]::Exception::" + e.what());
shutdown(context, "Exception in main function: " + std::string(e.what()));
return -1;
}

View File

@@ -33,10 +33,9 @@
#include <exception>
#include <dqrobotics/utils/DQ_Math.h>
#include <sas_common/sas_common.h>
#include <sas_conversions/eigen3_std_conversions.h>
#include <sas_robot_driver/sas_robot_driver_ros.h>
#include "sas_robot_driver_franka_hand.h"
#include <sas_common/sas_common.hpp>
// #include <sas_conversions/eigen3_std_conversions.hpp>
#include <sas_robot_driver_franka/interfaces/qros_effector_driver_franka_hand.hpp>
/*********************************************
@@ -49,67 +48,73 @@ void sig_int_handler(int)
kill_this_process = true;
}
template<typename T>
void get_optional_parameter(std::shared_ptr<Node> node, const std::string &param_name, T &param)
{
if(node->has_parameter(param_name))
{
sas::get_ros_parameter(node,param_name,param);
}else
{
RCLCPP_INFO_STREAM(node->get_logger(), "["+std::string(node->get_name())+"]:Parameter " + param_name + " not found. Using default value. " + std::to_string(param));
}
}
int main(int argc, char **argv)
{
if(signal(SIGINT, sig_int_handler) == SIG_ERR)
{
throw std::runtime_error(ros::this_node::getName() + "::Error setting the signal int handler.");
throw std::runtime_error("Error setting the signal int handler.");
}
ros::init(argc, argv, "sas_robot_driver_franka_hand_node", ros::init_options::NoSigintHandler);
ROS_WARN("=====================================================================");
ROS_WARN("---------------------------Quentin Lin-------------------------------");
ROS_WARN("=====================================================================");
ROS_INFO_STREAM(ros::this_node::getName()+"::Loading parameters from parameter server.");
rclcpp::init(argc,argv,rclcpp::InitOptions(),rclcpp::SignalHandlerOptions::None);
auto node = std::make_shared<rclcpp::Node>("sas_robot_driver_franka_hand_node");
ros::NodeHandle nh;
sas::RobotDriverFrankaHandConfiguration robot_driver_franka_hand_configuration;
const auto node_name = std::string(node->get_name());
RCLCPP_WARN(node->get_logger(),"=====================================================================");
RCLCPP_WARN(node->get_logger(),"---------------------------Quentin Lin-------------------------------");
RCLCPP_WARN(node->get_logger(),"=====================================================================");
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),"["+node_name+"]::Loading parameters from parameter server.");
sas::get_ros_param(nh,"/robot_ip_address",robot_driver_franka_hand_configuration.robot_ip);
qros::EffectorDriverFrankaHandConfiguration robot_driver_franka_hand_configuration;
sas::get_ros_parameter(node,"robot_ip_address",robot_driver_franka_hand_configuration.robot_ip);
sas::get_ros_parameter(node,"thread_sampling_time_sec",robot_driver_franka_hand_configuration.thread_sampeling_time_s);
sas::get_ros_parameter(node,"default_force",robot_driver_franka_hand_configuration.default_force);
sas::get_ros_parameter(node,"default_speed",robot_driver_franka_hand_configuration.default_speed);
sas::get_ros_parameter(node,"default_epsilon_inner",robot_driver_franka_hand_configuration.default_epsilon_inner);
sas::get_ros_parameter(node,"default_epsilon_outer",robot_driver_franka_hand_configuration.default_epsilon_outer);
sas::RobotDriverROSConfiguration robot_driver_ros_configuration;
sas::get_ros_param(nh,"/thread_sampling_time_nsec",robot_driver_ros_configuration.thread_sampling_time_nsec);
bool q_lim_override = false;
if(nh.hasParam("q_min") || nh.hasParam("q_max"))
{
sas::get_ros_param(nh,"/q_min",robot_driver_ros_configuration.q_min);
sas::get_ros_param(nh,"/q_max",robot_driver_ros_configuration.q_max);
q_lim_override = true;
}else
{
}
robot_driver_ros_configuration.robot_driver_provider_prefix = ros::this_node::getName();
sas::RobotDriverFrankaHand franka_hand_driver(
qros::EffectorDriverFrankaHand franka_hand_driver(
node_name,
robot_driver_franka_hand_configuration,
robot_driver_ros_configuration,
node,
&kill_this_process
);
try
{
ROS_INFO_STREAM(ros::this_node::getName()+"::Instantiating Franka hand.");
RCLCPP_INFO_STREAM(node->get_logger(),"["+node_name+"]::Instantiating Franka hand.");
franka_hand_driver.connect();
franka_hand_driver.initialize();
ROS_INFO_STREAM(ros::this_node::getName()+"::Instantiating control loop.");
RCLCPP_INFO_STREAM(node->get_logger(),"["+node_name+"]::Starting control loop.");
franka_hand_driver.start_control_loop();
}
catch (const std::exception& e)
{
ROS_ERROR_STREAM(ros::this_node::getName() + "::Exception::" + e.what());
RCLCPP_ERROR_STREAM(node->get_logger(), "["+node_name+"]::Exception::" + e.what());
}catch (...)
{
ROS_ERROR_STREAM(ros::this_node::getName() + "::Exception::Unknown exception.");
RCLCPP_ERROR_STREAM(node->get_logger(), "["+node_name+"]::Exception::Unknown exception.");
}
ROS_INFO_STREAM(ros::this_node::getName()+"::Exiting...");
RCLCPP_INFO_STREAM(node->get_logger(),"["+node_name+"]::Exiting...");
franka_hand_driver.deinitialize();
ROS_INFO_STREAM(ros::this_node::getName()+"::deinitialized.");
RCLCPP_INFO_STREAM(node->get_logger(),"["+node_name+"]::Deinitialized.");
franka_hand_driver.disconnect();
ROS_INFO_STREAM(ros::this_node::getName()+"::disconnected.");
RCLCPP_INFO_STREAM(node->get_logger(),"["+node_name+"]::Disconnected.");
return 0;

View File

@@ -26,6 +26,8 @@
# 1. Juan Jose Quiroz Omana (juanjqogm@gmail.com)
# - Adapted from sas_robot_driver_denso_node.cpp
# (https://github.com/SmartArmStack/sas_robot_driver_denso/blob/master/src/sas_robot_driver_denso_node.cpp)
# 2. Quentin Lin
# - Adaption to ROS2
#
# ################################################################
*/
@@ -35,12 +37,12 @@
#include <exception>
#include <dqrobotics/utils/DQ_Math.h>
//#include <dqrobotics/interfaces/json11/DQ_JsonReader.h>
#include <sas_common/sas_common.h>
#include <sas_conversions/eigen3_std_conversions.h>
#include <sas_robot_driver/sas_robot_driver_ros.h>
#include "sas_robot_driver_franka.h"
#include "sas_robot_dynamic_provider.h"
#include <dqrobotics/interfaces/json11/DQ_JsonReader.h>
#include <sas_common/sas_common.hpp>
#include <sas_conversions/eigen3_std_conversions.hpp>
#include <sas_robot_driver/sas_robot_driver_ros.hpp>
#include <sas_robot_driver_franka/sas_robot_driver_franka.hpp>
#include <sas_robot_driver_franka/robot_dynamic/qros_robot_dynamics_server.hpp>
/*********************************************
@@ -74,80 +76,106 @@ std::array<T, N> std_vec_to_std_array(const std::vector<T>& vector)
}
return array;
}
VectorXd std_vec_to_eigen_vector(const std::vector<double>& vector)
{
VectorXd eigen_vector(vector.size());
for(std::size_t i = 0; i < vector.size(); i++)
{
eigen_vector(i) = vector[i];
}
return eigen_vector;
}
int main(int argc, char **argv)
{
if(signal(SIGINT, sig_int_handler) == SIG_ERR)
{
throw std::runtime_error(ros::this_node::getName() + "::Error setting the signal int handler.");
throw std::runtime_error("Error setting the signal int handler.");
}
ros::init(argc, argv, "sas_robot_driver_franka_node", ros::init_options::NoSigintHandler);
ROS_WARN("=====================================================================");
ROS_WARN("----------------------Juan Jose Quiroz Omana------------------------");
ROS_WARN("=====================================================================");
ROS_INFO_STREAM(ros::this_node::getName()+"::Loading parameters from parameter server.");
rclcpp::init(argc,argv,rclcpp::InitOptions(),rclcpp::SignalHandlerOptions::None);
auto node = std::make_shared<rclcpp::Node>("sas_robot_driver_franka_node");
const auto node_name = std::string(node->get_name());
RCLCPP_WARN(node->get_logger(),"=====================================================================");
RCLCPP_WARN(node->get_logger(),"-----------------Adapted by Quentin Lin ------------------------");
RCLCPP_WARN(node->get_logger(),"=====================================================================");
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),"["+node_name+"]::Loading parameters from parameter server.");
ros::NodeHandle nh;
sas::RobotDriverFrankaConfiguration robot_driver_franka_configuration;
RobotInterfaceFranka::FrankaInterfaceConfiguration franka_interface_configuration;
sas::get_ros_param(nh,"/robot_ip_address",robot_driver_franka_configuration.ip_address);
sas::get_ros_param(nh,"/robot_mode", robot_driver_franka_configuration.mode);
sas::get_ros_parameter(node,"robot_ip_address",robot_driver_franka_configuration.ip_address);
sas::get_ros_parameter(node,"robot_mode", robot_driver_franka_configuration.mode);
double upper_scale_factor = 1.0;
std::vector<std::string> all_params;
if(nh.hasParam(ros::this_node::getName()+"/force_upper_limits_scaling_factor"))
{
sas::get_ros_param(nh,"/force_upper_limits_scaling_factor",upper_scale_factor);
ROS_WARN_STREAM(ros::this_node::getName()+"::Set force upper limits scaling factor: " << upper_scale_factor);
}
if(nh.hasParam(ros::this_node::getName()+"/upper_torque_threshold")) {
ROS_INFO_STREAM(ros::this_node::getName()+"::Upper torque threshold override and set.");
std::vector<double> upper_torque_threshold_std_vec;
sas::get_ros_param(nh,"/upper_torque_threshold",upper_torque_threshold_std_vec);
franka_interface_configuration.upper_torque_threshold = std_vec_to_std_array<double,7>(upper_torque_threshold_std_vec);
}else {
ROS_INFO_STREAM(ros::this_node::getName()+"::Upper torque threshold not set. Using default with value scalling.");
franka_interface_configuration.upper_torque_threshold = apply_scale_to_std_array(franka_interface_configuration.upper_torque_threshold, upper_scale_factor);
}
if(nh.hasParam(ros::this_node::getName()+"/upper_force_threshold")) {
ROS_INFO_STREAM(ros::this_node::getName()+"::Upper force threshold override and set.");
std::vector<double> upper_torque_threshold_std_vec;
sas::get_ros_param(nh,"/upper_force_threshold",upper_torque_threshold_std_vec);
franka_interface_configuration.upper_force_threshold = std_vec_to_std_array<double,6>(upper_torque_threshold_std_vec);
}else {
ROS_INFO_STREAM(ros::this_node::getName()+"::Upper force threshold not set. Using default with value scalling.");
franka_interface_configuration.upper_force_threshold = apply_scale_to_std_array(franka_interface_configuration.upper_force_threshold, upper_scale_factor);
try {
sas::get_ros_parameter(node,"force_upper_limits_scaling_factor",upper_scale_factor);
RCLCPP_WARN_STREAM_ONCE(node->get_logger(),"Set force upper limits scaling factor: " << upper_scale_factor);
}catch(...) {
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),"Force upper limits scaling factor is not set.");
}
try {
std::vector<double> upper_torque_threshold_std_vec;
sas::get_ros_parameter(node,"upper_torque_threshold",upper_torque_threshold_std_vec);
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),"["+node_name+"]::Upper torque threshold override and set.");
franka_interface_configuration.upper_torque_threshold = std_vec_to_std_array<double,7>(upper_torque_threshold_std_vec);
}catch(...) {
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),"["+node_name+"]::Upper torque threshold not set. Using default with value scalling.");
franka_interface_configuration.upper_torque_threshold = apply_scale_to_std_array(franka_interface_configuration.upper_torque_threshold, upper_scale_factor);
}
try {
std::vector<double> upper_force_threshold_std_vec;
sas::get_ros_parameter(node,"upper_force_threshold",upper_force_threshold_std_vec);
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),"["+node_name+"]::Upper force threshold override and set.");
franka_interface_configuration.upper_force_threshold = std_vec_to_std_array<double,6>(upper_force_threshold_std_vec);
}catch(...) {
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),"["+node_name+"]::Upper torque threshold not set. Using default with value scalling.");
franka_interface_configuration.upper_force_threshold = apply_scale_to_std_array(franka_interface_configuration.upper_force_threshold, upper_scale_factor);
}
try {
std::string robot_parameter_file_path;
sas::get_ros_parameter(node,"robot_parameter_file_path",robot_parameter_file_path);
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),"["+node_name+"]::Loading robot parameters from file: " + robot_parameter_file_path);
const auto robot = DQ_JsonReader::get_from_json<DQ_SerialManipulatorDH>(robot_parameter_file_path);
robot_driver_franka_configuration.robot_reference_frame = robot.get_reference_frame();
}catch(...) {
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),"["+node_name+"]::Robot parameter file path not set. Robot Model Unknow.");
}
robot_driver_franka_configuration.interface_configuration = franka_interface_configuration;
sas::RobotDriverROSConfiguration robot_driver_ros_configuration;
sas::get_ros_param(nh,"/thread_sampling_time_nsec",robot_driver_ros_configuration.thread_sampling_time_nsec);
sas::get_ros_param(nh,"/q_min",robot_driver_ros_configuration.q_min);
sas::get_ros_param(nh,"/q_max",robot_driver_ros_configuration.q_max);
sas::get_ros_parameter(node,"thread_sampling_time_sec",robot_driver_ros_configuration.thread_sampling_time_sec);
sas::get_ros_parameter(node,"q_min",robot_driver_ros_configuration.q_min);
sas::get_ros_parameter(node,"q_max",robot_driver_ros_configuration.q_max);
// initialize the robot dynamic provider
robot_driver_ros_configuration.robot_driver_provider_prefix = ros::this_node::getName();
sas::RobotDynamicProvider robot_dynamic_provider(nh, robot_driver_ros_configuration.robot_driver_provider_prefix);
robot_driver_ros_configuration.robot_driver_provider_prefix = node_name;
std::shared_ptr<qros::RobotDynamicsServer> robot_dynamic_provider_ptr = std::make_shared<qros::RobotDynamicsServer>(node, robot_driver_ros_configuration.robot_driver_provider_prefix);
if(robot_driver_franka_configuration.robot_reference_frame!=0)
{
robot_dynamic_provider_ptr->set_world_to_base_tf(robot_driver_franka_configuration.robot_reference_frame);
}
try
{
ROS_INFO_STREAM(ros::this_node::getName()+"::Instantiating Franka robot.");
sas::RobotDriverFranka robot_driver_franka(
&robot_dynamic_provider,
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),"["+node_name+"]::Instantiating Franka robot.");
auto robot_driver_franka = std::make_shared<sas::RobotDriverFranka>(
node,
robot_dynamic_provider_ptr,
robot_driver_franka_configuration,
&kill_this_process
);
//robot_driver_franka.set_joint_limits({qmin, qmax});
ROS_INFO_STREAM(ros::this_node::getName()+"::Instantiating RobotDriverROS.");
sas::RobotDriverROS robot_driver_ros(nh,
&robot_driver_franka,
std::tuple<VectorXd, VectorXd> joint_limits = {std_vec_to_eigen_vector(robot_driver_ros_configuration.q_min), std_vec_to_eigen_vector(robot_driver_ros_configuration.q_max)};
robot_driver_franka -> set_joint_limits(joint_limits);
RCLCPP_INFO_STREAM_ONCE(node->get_logger(),"["+node_name+"]::Instantiating RobotDriverROS.");
sas::RobotDriverROS robot_driver_ros(node,
robot_driver_franka,
robot_driver_ros_configuration,
&kill_this_process);
robot_driver_ros.control_loop();
@@ -155,7 +183,7 @@ int main(int argc, char **argv)
catch (const std::exception& e)
{
kill_this_process = true;
ROS_ERROR_STREAM(ros::this_node::getName() + "::Exception::" + e.what());
RCLCPP_ERROR_STREAM_ONCE(node->get_logger(),"["+node_name+"]::Exception::" + e.what());
}