From 07586c466fdf27b9dc2b3bb26115910d211e8739 Mon Sep 17 00:00:00 2001 From: Thomas Date: Sun, 7 Jan 2024 22:58:40 +0100 Subject: [PATCH] Copy to new git --- CMakeLists.txt | 235 +++++++++++++++++++++++++++++++++++++++++++++ DynamixelHandler.h | 82 ++++++++++++++++ ik_client.cpp | 51 ++++++++++ ik_server.cpp | 30 ++++++ package.xml | 65 +++++++++++++ poppy_dh.yaml | 11 +++ poppy_ik.yaml | 6 ++ poppy_ros.cpp | 109 +++++++++++++++++++++ poppy_state.cpp | 95 ++++++++++++++++++ 9 files changed, 684 insertions(+) create mode 100644 CMakeLists.txt create mode 100644 DynamixelHandler.h create mode 100644 ik_client.cpp create mode 100644 ik_server.cpp create mode 100644 package.xml create mode 100644 poppy_dh.yaml create mode 100644 poppy_ik.yaml create mode 100644 poppy_ros.cpp create mode 100644 poppy_state.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..0c8d2ef --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,235 @@ +cmake_minimum_required(VERSION 3.0.2) +project(poppy_ros) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +set (OpenCV_DIR "/usr/lib/opencv") + +## 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 + std_msgs + geometry_msgs + message_generation + poppy_ros +) + +find_package(OpenCV REQUIRED COMPONENTS + core +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +##add_service_files( + ## FILES + ##ik.srv +##) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + std_msgs + geometry_msgs +) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES poppy_ros +# CATKIN_DEPENDS roscpp std_msgs +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( + /home/ros/SOFTWARE/toolkit-dynamixel + /home/ros/SOFTWARE/toolkit-kinematics + ${OpenCV_INCLUDE_DIRS} + /home/ros/SOFTWARE/eigen/Eigen + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/poppy_ros.cpp +# ) + +#add_library(poppy_ros src/$DynamixelHandler.cpp) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/poppy_ros_node.cpp) +add_executable(poppy_state ~/catkin_ws/src/lab3/poppy_state.cpp /home/ros/SOFTWARE/toolkit-dynamixel/src/DynamixelHandler.cpp) + +add_executable(poppy_ros ~/catkin_ws/src/lab3/poppy_ros.cpp /home/ros/SOFTWARE/toolkit-dynamixel/src/DynamixelHandler.cpp) + +#add_executable(ik_server src/ik_server.cpp src/toolkit-kinematics/Kinematics.cpp src/toolkit-kinematics/RotationMatrix.cpp src/toolkit-kinematics/TranslationMatrix.cpp src/toolkit-kinematics/TransformationMatrix.cpp) + +#add_executable(ik_client src/ik_client.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +target_link_libraries(poppy_state dxl_x64_cpp rt ${catkin_LIBRARIES}) +target_link_libraries(poppy_ros dxl_x64_cpp rt ${catkin_LIBRARIES}) + +#target_link_libraries(ik_server ${catkin_LIBRARIES} ${OpenCV_LIBS}) + +#target_link_libraries(ik_client ${catkin_LIBRARIES}) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +#include /home/ros/SOFTWARE/toolkit-dynamixel/include/DynamixelHandler.h +include_directories(/home/ros/SOFTWARE/toolkit-dynamixel/include) +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_poppy_ros.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/DynamixelHandler.h b/DynamixelHandler.h new file mode 100644 index 0000000..099d433 --- /dev/null +++ b/DynamixelHandler.h @@ -0,0 +1,82 @@ +#if defined(__linux__) || defined(__APPLE__) +#include +#include +#include +#define STDIN_FILENO 0 +#elif defined(_WIN32) || defined(_WIN64) +#include +#endif + +#include +#include +#include +#include +#include + +#include "dynamixel_sdk/dynamixel_sdk.h" + + +#define ADDR_XL320_TORQUE_ENABLE 24 +#define ADDR_XL320_LED_ON 25 + +#define ADDR_XL320_D_GAIN 27 +#define ADDR_XL320_I_GAIN 28 +#define ADDR_XL320_P_GAIN 29 + +#define ADDR_XL320_GOAL_POSITION 30 +#define ADDR_XL320_GOAL_VELOCITY 32 +#define ADDR_XL320_GOAL_TORQUE 35 + +#define ADDR_XL320_PRESENT_POSITION 37 +#define ADDR_XL320_PRESENT_VELOCITY 39 +#define ADDR_XL320_PRESENT_LOAD 41 +#define ADDR_XL320_PRESENT_VOLTAGE 45 +#define ADDR_XL320_PRESENT_TEMPERATURE 46 + +#define ADDR_XL320_HARDWARE_ERROR_STATUS 50 + +#define NB_JOINTS 6 + + +class DynamixelHandler +{ + +public: + DynamixelHandler(); + ~DynamixelHandler(); + +public: + //scan(); + //ping(); + //reboot(); + bool openPort(); + void closePort(); + bool setBaudRate(int); + void setDeviceName(std::string); + void setProtocolVersion(float); + bool enableTorque(bool); + + bool readCurrentJointPosition(std::vector& vCurrentJointPosition); + bool readCurrentJointTorque(std::vector& vCurrentJointTorque); + bool sendTargetJointPosition(std::vector& vTargetJointPosition); + + + +private: + std::string m_sDeviceName; + float m_fProtocolVersion; + int m_i32BaudRate; + + dynamixel::PortHandler* m_pPortHandler; + dynamixel::PacketHandler* m_pPacketHandler; + + bool m_bIsDeviceNameSet; + bool m_bIsProtocolVersionSet; + bool m_bIsPortOpened; + bool m_bIsBaudRateSet; + + int m_i32DxlCommunicationResult; // Communication result + uint8_t m_ui8DxlError; // Dynamixel error + std::vector m_vDxlCurrentPosition; // Present position + +}; \ No newline at end of file diff --git a/ik_client.cpp b/ik_client.cpp new file mode 100644 index 0000000..b1e7dde --- /dev/null +++ b/ik_client.cpp @@ -0,0 +1,51 @@ +#include +#include "ros/ros.h" +#include "poppy_ros/InverseKinematics.h" +#include "geometry_msgs/Twist.h" + +int main(int argc, char** argv) +{ + if (argc != 4) + { + std::cerr << "Usage: rosrun poppy_ros ik_client " << std::endl; + return 1; + } + + ros::init(argc, argv, "ik_client"); + ros::NodeHandle nh; + ros::ServiceClient ikClient = nh.serviceClient("ik"); + + poppy_ros::InverseKinematics srv; + srv.request.x = std::stof(argv[1]); + srv.request.y = std::stof(argv[2]); + srv.request.z = std::stof(argv[3]); + + if (ikClient.call(srv)) + { + ROS_INFO("Received joint values from ik_server."); + + ros::Publisher jointCmdPublisher = nh.advertise("/joint_cmd", 1); + geometry_msgs::Twist jointCmdMsg; + + // Assign the received joint values to the Twist message + jointCmdMsg.linear.x = srv.response.joint1; + jointCmdMsg.linear.y = srv.response.joint2; + jointCmdMsg.linear.z = srv.response.joint3; + jointCmdMsg.angular.x = srv.response.joint4; + jointCmdMsg.angular.y = srv.response.joint5; + jointCmdMsg.angular.z = srv.response.joint6; + + // Publish joint values to the topic /joint_cmd + jointCmdPublisher.publish(jointCmdMsg); + + ROS_INFO("Published joint values to /joint_cmd."); + } + else + { + ROS_ERROR("Failed to call ik service."); + return 1; + } + + return 0; +} + diff --git a/ik_server.cpp b/ik_server.cpp new file mode 100644 index 0000000..7c4d778 --- /dev/null +++ b/ik_server.cpp @@ -0,0 +1,30 @@ +#include "ros/ros.h" +#include "poppy_ros/InverseKinematics.h" + +bool inverseKinematicsService(poppy_ros::InverseKinematics::Request& req, poppy_ros::InverseKinematics::Response& res) +{ + + res.joint1 = req.x; + res.joint2 = req.y; + res.joint3 = req.z; + res.joint4 = 0.0; + res.joint5 = 0.0; + res.joint6 = 0.0; + + return true; +} + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "ik_server"); + ros::NodeHandle nh; + + ros::ServiceServer server = nh.advertiseService("ik", inverseKinematicsService); + + ROS_INFO("ik_server is ready to receive requests."); + + ros::spin(); + + return 0; +} + diff --git a/package.xml b/package.xml new file mode 100644 index 0000000..d3cfd04 --- /dev/null +++ b/package.xml @@ -0,0 +1,65 @@ + + + poppy_ros + 0.0.0 + The poppy_ros package + + + + + ros + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + message_generation + + + + + + message_runtime + + + + + catkin + roscpp + std_msgs + roscpp + std_msgs + roscpp + std_msgs + + + + + + + + \ No newline at end of file diff --git a/poppy_dh.yaml b/poppy_dh.yaml new file mode 100644 index 0000000..566c147 --- /dev/null +++ b/poppy_dh.yaml @@ -0,0 +1,11 @@ +%YAML:1.0 +--- +dhThetaParams: [ 0., 0., 0., 0., 0., 0., 0. ] +dhDParams: [ 2.5000000000000000e+00, 2.5000000000000000e+00, 0., 0., 0., + 0., 0. ] +dhAParams: [ 0., 0., 5.5000000000000000e+00, 3., 0., 5., 12. ] +dhAlphaParams: [ 0., 90., 0., 0., -90., 90., 0. ] +jointType: [ 0, 1, 1, 1, 0, 1, 1 ] +nbJoints: 5 +jointOffset: [ 0., 0., 90., 0., -90., 0., 0. ] +qiValues: [ 0., 0., 0., 0., 90. ] diff --git a/poppy_ik.yaml b/poppy_ik.yaml new file mode 100644 index 0000000..7605a03 --- /dev/null +++ b/poppy_ik.yaml @@ -0,0 +1,6 @@ +%YAML:1.0 +--- +maxNbIterations: 1000 +pController: 0.5 +rankThreshold: 0.2 +distanceThreshold: 0.01 diff --git a/poppy_ros.cpp b/poppy_ros.cpp new file mode 100644 index 0000000..217f6ba --- /dev/null +++ b/poppy_ros.cpp @@ -0,0 +1,109 @@ +#include "DynamixelHandler.h" +#include +#include + + +// Global variables +float _fps = 10.0f; // Hz + +DynamixelHandler dxHandler; +ros::Publisher _jointPositionPublisher; +int _nbJoints = 6; +float _minJointCmd = 0; +float _maxJointCmd = 1023; +float _minJointAngle = -180.0f; +float _maxJointAngle = 180.0f; + +int convertAnglesToJointCmd(float fJointAngle) +{ + // y = ax + b + float a = (_maxJointCmd-_minJointCmd) / (_maxJointAngle - _minJointAngle); + float b = _minJointCmd - a * _minJointAngle; + float jointCmd = a * fJointAngle + b; + return (int)jointCmd; +} + +void jointCallback(const geometry_msgs::Twist & joint_cmd){ + + int joint1 = convertAnglesToJointCmd(joint_cmd.linear.x); + int joint2 = convertAnglesToJointCmd(joint_cmd.linear.y); + int joint3 = convertAnglesToJointCmd(joint_cmd.linear.z); + int joint4 = convertAnglesToJointCmd(joint_cmd.angular.x); + int joint5 = convertAnglesToJointCmd(joint_cmd.angular.y); + int joint6 = convertAnglesToJointCmd(joint_cmd.angular.z); + + std::vector jointvec; + + jointvec.push_back(joint1); + jointvec.push_back(joint2); + jointvec.push_back(joint3); + jointvec.push_back(joint4); + jointvec.push_back(joint5); + jointvec.push_back(joint6); + + dxHandler.sendTargetJointPosition(jointvec); + +} + + +int main(int argc, char** argv) +{ + // create a node called poppy_ros + ros::init(argc, argv, "poppy_ros", ros::init_options::NoSigintHandler); + //ros::init(argc, argv, "autopilot"); + + // create a node handle + ros::NodeHandle nh; + + // create a publisher to joint_position topic + _jointPositionPublisher = nh.advertise("joint_position", 1); + + // create a loop rate + ros::Rate loopRate(_fps); + + // create a Twist message + geometry_msgs::Twist jointPositionMsg; + + std::cout << "===Initialization of the Dynamixel Motor communication====" << std::endl; + dxHandler.setDeviceName("/dev/ttyUSB0"); + dxHandler.setProtocolVersion(2.0); + dxHandler.openPort(); + dxHandler.setBaudRate(1000000); + dxHandler.enableTorque(false); + std::cout << std::endl; + ROS_INFO("===Launching Poppy node==="); + + + // loop until Ctrl+C is pressed or ROS connectivity issues + while(ros::ok()) + { + //===RETRIEVE Dynamixel Motor positions==== + std::vector l_vCurrentJointPosition; + bool bIsReadSuccessfull = dxHandler.readCurrentJointPosition(l_vCurrentJointPosition); + + // stores them into a msg + if (bIsReadSuccessfull) + { + jointPositionMsg.linear.x = l_vCurrentJointPosition[0]; + jointPositionMsg.linear.y = l_vCurrentJointPosition[1]; + jointPositionMsg.linear.z = l_vCurrentJointPosition[2]; + jointPositionMsg.angular.x = l_vCurrentJointPosition[3]; + jointPositionMsg.angular.y = l_vCurrentJointPosition[4]; + jointPositionMsg.angular.z = l_vCurrentJointPosition[5]; + } + + // publish the Twist message to the joint_position topic + _jointPositionPublisher.publish(jointPositionMsg); + + // spin once to let the process handle callback ad key stroke + ros::spinOnce(); + + // sleep the right amout of time to comply with _fps + loopRate.sleep(); + } + + dxHandler.enableTorque(false); + dxHandler.closePort(); + + return 0; +} diff --git a/poppy_state.cpp b/poppy_state.cpp new file mode 100644 index 0000000..c6b8af8 --- /dev/null +++ b/poppy_state.cpp @@ -0,0 +1,95 @@ +#include "DynamixelHandler.h" + +#include +#include + + +// Global variables +float _fps = 10.0f; // Hz + +DynamixelHandler _oDxlHandler; +ros::Publisher _jointPositionPublisher; +std::string _poppyDxlPortName = "/dev/ttyUSB0"; +float _poppyDxlProtocol = 2.0; +int _poppyDxlBaudRate = 1000000; +int _nbJoints = 6; +float _minJointCmd = 0; +float _maxJointCmd = 1023; +float _minJointAngle = -180.0f; +float _maxJointAngle = 180.0f; + + + +int convertAnglesToJointCmd(float fJointAngle) +{ + // y = ax + b + float a = (_maxJointCmd-_minJointCmd) / (_maxJointAngle - _minJointAngle); + float b = _minJointCmd - a * _minJointAngle; + float jointCmd = a * fJointAngle + b; + return (int)jointCmd; +} + + +int main(int argc, char** argv) +{ + // create a node called poppy_ros + ros::init(argc, argv, "poppy_ros", ros::init_options::NoSigintHandler); + //ros::init(argc, argv, "autopilot"); + + // create a node handle + ros::NodeHandle nh; + + // create a publisher to joint_position topic + _jointPositionPublisher = nh.advertise("joint_position", 1); + + // create a loop rate + ros::Rate loopRate(_fps); + + // create a Twist message + geometry_msgs::Twist jointPositionMsg; + + std::cout << "===Initialization of the Dynamixel Motor communication====" << std::endl; + _oDxlHandler.setDeviceName(_poppyDxlPortName); + _oDxlHandler.setProtocolVersion(_poppyDxlProtocol); + _oDxlHandler.openPort(); + _oDxlHandler.setBaudRate(_poppyDxlBaudRate); + _oDxlHandler.enableTorque(false); + std::cout << std::endl; + + + + ROS_INFO("===Launching Poppy node==="); + + // loop until Ctrl+C is pressed or ROS connectivity issues + while(ros::ok()) + { + //===RETRIEVE Dynamixel Motor positions==== + std::vector l_vCurrentJointPosition; + bool bIsReadSuccessfull = _oDxlHandler.readCurrentJointPosition(l_vCurrentJointPosition); + + // stores them into a msg + if (bIsReadSuccessfull) + { + jointPositionMsg.linear.x = l_vCurrentJointPosition[0]; + jointPositionMsg.linear.y = l_vCurrentJointPosition[1]; + jointPositionMsg.linear.z = l_vCurrentJointPosition[2]; + jointPositionMsg.angular.x = l_vCurrentJointPosition[3]; + jointPositionMsg.angular.y = l_vCurrentJointPosition[4]; + jointPositionMsg.angular.z = l_vCurrentJointPosition[5]; + } + + // publish the Twist message to the joint_position topic + _jointPositionPublisher.publish(jointPositionMsg); + + // spin once to let the process handle callback ad key stroke + ros::spinOnce(); + + // sleep the right amout of time to comply with _fps + loopRate.sleep(); + } + + _oDxlHandler.enableTorque(false); + _oDxlHandler.closePort(); + + return 0; +}