This commit is contained in:
Charles Yvan EBELLE DIBOBE 2023-01-01 23:32:18 +01:00
parent f1269de82b
commit c4c2eba301
9 changed files with 522 additions and 0 deletions

227
CMakeLists.txt Normal file
View File

@ -0,0 +1,227 @@
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
roscpp
std_msgs
geometry_msgs
message_generation
)
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 other_catkin_pkg
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
/home/charlesyvan/catkin_ws/src/poppy_ros/src/toolkit-dynamixel/include
/home/charlesyvan/catkin_ws/src/poppy_ros/src/toolkit-kinematics/include
${OpenCV_INCLUDE_DIRS}
/home/charlesyvan/catkin_ws/src/poppy_ros/src/eigen/Eigen
${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/poppy_ros.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(poppy_ros src/poppy_ros.cpp src/toolkit-dynamixel/src/DynamixelHandler.cpp)
add_executable(ik_server src/ik_server.cpp src/toolkit-kinematics/src/Kinematics.cpp src/toolkit-kinematics/src/RotationMatrix.cpp src/toolkit-kinematics/src/TranslationMatrix.cpp src/toolkit-kinematics/src/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})
add_dependencies(ik_server poppy_ros_gencpp)
add_dependencies(ik_client poppy_ros_gencpp)
## Specify libraries to link a library or executable target against
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
# )
## 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)

65
package.xml Normal file
View File

@ -0,0 +1,65 @@
<?xml version="1.0"?>
<package format="2">
<name>poppy_ros</name>
<version>0.0.0</version>
<description>The poppy_ros package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="ros@todo.todo">ros</maintainer>
<!-- 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>
<!-- 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/poppy_ros</url> -->
<!-- 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>std_msgs</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>std_msgs</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>

1
src/eigen Submodule

@ -0,0 +1 @@
Subproject commit 311cc0f9cc66fa49523bbcb45a9ba22363fdd65a

76
src/ik_client.cpp Normal file
View File

@ -0,0 +1,76 @@
#include "ros/ros.h"
#include <geometry_msgs/Twist.h>
#include <sensor_msgs/JointState.h>
#include "poppy_ros/ik.h"
// import the definition of the service, this file was automatically generated from the file ik.srv
#include "math.h"
float _fps = 10.0;
double deg2rad(double angle)
{
return angle / 180.0 * M_PI;
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "ik_client");
if (argc != 4)
{
ROS_INFO("usage: rosrun poppy_ros ik_client x y z");
ROS_INFO("ex.: rosrun poppy_ros ik_client 12.07 7.05 18.4");
return 1;
}
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<poppy_ros::ik>("ik");
// TODO: create a publisher to the joint_cmd topic if you work with the real robot or the joint_states topic if you work with the virtual robot
ros::Publisher jointCmdPublisher =
nh.advertise<sensor_msgs::JointState>("joint_states",1);
poppy_ros::ik srv;
// TODO: create the request using the args: x = atof(argv[1]), y = atof(argv[2]) and z = atof(argv[3])
srv.request.world_pos.linear.x = atof(argv[1]);
srv.request.world_pos.linear.y = atof(argv[2]);
srv.request.world_pos.linear.z = atof(argv[3]);
// create a loop rate
ros::Rate loopRate(_fps);
if (client.call(srv)) // call the service
{
ROS_INFO("Input: (x, y, z) = (%f, %f, %f)", atof(argv[1]), atof(argv[2]), atof(argv[3]));
//TODO: the response from the ik server is in the variable srv.response
std::vector<double>jointCmdValueArray = {deg2rad(srv.response.joint_pos.linear.x), deg2rad(srv.response.joint_pos.linear.y), deg2rad(srv.response.joint_pos.linear.z), deg2rad(srv.response.joint_pos.angular.x), deg2rad(srv.response.joint_pos.angular.y), deg2rad(srv.response.joint_pos.angular.z)};
std::vector<std::string>jointCmdNameArray = {"m1", "m2", "m3", "m4", "m5", "m6"};
while (ros::ok())
{
// TODO: create a message to publish to the topic joint_cmd or joint_states using the srv.response data
sensor_msgs::JointState jointCmdMsg;
jointCmdMsg.header.stamp = ros::Time::now();
jointCmdMsg.header.seq++;
jointCmdMsg.position = jointCmdValueArray;
jointCmdMsg.name = jointCmdNameArray;
// TODO: publish the message
jointCmdPublisher.publish(jointCmdMsg);
ros::spinOnce();
loopRate.sleep();
}
}
else
{
ROS_ERROR("Failed to call the service ik!");
return 1;
}
return 0;
}

66
src/ik_server.cpp Normal file
View File

@ -0,0 +1,66 @@
#include "ros/ros.h"
#include <geometry_msgs/Twist.h>
#include "poppy_ros/ik.h"
#include "/home/charlesyvan/catkin_ws/src/poppy_ros/src/toolkit-kinematics/include/Kinematics.h"
poppy_ros::ik service;
Kinematics _kinematics; // create a Kinematics object
cv::Mat _oXTarget(3, 1, CV_64F, 0.0); // create a matrix to store the (x,y,z) end-effector position to pass it to the inverse kinematics function
bool ik(poppy_ros::ik::Request &request, poppy_ros::ik::Response &response) //callback function for the server
{
_oXTarget.at<double>(0,0) = request.world_pos.linear.x;
_oXTarget.at<double>(1,0) = request.world_pos.linear.y;
_oXTarget.at<double>(2,0) = request.world_pos.linear.z;
_kinematics.inverseKinematics(_oXTarget); // call the inverse kinematics function
std::vector<double> l_vQi = _kinematics.getQiValues(); // retrieve the 5 joint values computed by the inverse kinematics functions
// Create the response
// using the 5 joint values : l_vQi[0], l_vQi[1], l_vQi[2], l_vQi[3], l_vQi[4]
response.joint_pos.linear.x = l_vQi[0];
response.joint_pos.linear.y = l_vQi[1];
response.joint_pos.linear.z = l_vQi[2];
response.joint_pos.angular.x = l_vQi[3];
response.joint_pos.angular.y = l_vQi[4];
response.joint_pos.angular.z = l_vQi[5];
return true;
}
int main(int argc, char** argv)
{
// process args
if (argc != 3 && argc != 4)
{
ROS_INFO("usage: rosrun poppy_ros ik_server <dhParamsFile> <ikParamsFile>");
ROS_INFO("ex.: rosrun poppy_ros ik_server /home/ros/_eeng/_eeng4/poppy_dh.yaml /home/ros/_eeng/_eeng4/poppy_ik.yaml");
return 1;
}
if (argc >= 2)
{
_kinematics.loadDHParameters(argv[1]);
}
if (argc >= 3)
{
_kinematics.loadIKParameters(argv[2]);
}
cv::Mat l_oCurrentEndEffectorPosition(4, 1, CV_64F, 0.0f);
l_oCurrentEndEffectorPosition = _kinematics.computeCurrentEndEffectorPosition();
ROS_INFO("Current End-effector position = (%f, %f, %f)", l_oCurrentEndEffectorPosition.at<double>(0, 0), l_oCurrentEndEffectorPosition.at<double>(1, 0), l_oCurrentEndEffectorPosition.at<double>(2, 0) );
// ROS
ros::init(argc, argv, "ik_server");
ros::NodeHandle nh;
ros::ServiceServer service = nh.advertiseService("ik", ik);
ROS_INFO("IK server launched...");
ros::spin();
return 0;
}

80
src/poppy_ros.cpp Normal file
View File

@ -0,0 +1,80 @@
#include <ros/ros.h>
#include <iostream>
#include <DynamixelHandler.h>
#include <geometry_msgs/Twist.h>
//global variable
DynamixelHandler dxHandler;
int _nbJoints = 6;
float _minJointCmd = 0;
float _maxJointCmd = 1023;
float _minJointAngle = -180.0f;
float _maxJointAngle = 180.0f;
//convert the angle in degrees to motor command
int convertAngleToMotorcmd (float fJointAngle)
{
float a = (_maxJointCmd-_minJointCmd) / (_maxJointAngle - _minJointAngle);
float b = _minJointCmd - a * _minJointAngle;
float jointCmd = a * fJointAngle + b;
return (int)jointCmd;
}
void driverCallback (const geometry_msgs::Twist msg)
{
std::vector<uint16_t> _TargetJointPosition;
_TargetJointPosition.push_back(convertAngleToMotorcmd(msg.linear.x));
_TargetJointPosition.push_back(convertAngleToMotorcmd(msg.linear.y));
_TargetJointPosition.push_back(convertAngleToMotorcmd(msg.linear.z));
_TargetJointPosition.push_back(convertAngleToMotorcmd(msg.angular.x));
_TargetJointPosition.push_back(convertAngleToMotorcmd(msg.angular.y));
_TargetJointPosition.push_back(convertAngleToMotorcmd(msg.angular.z));
dxHandler.sendTargetJointPosition(_TargetJointPosition);
}
int main(int argc, char **argv)
{
//connect to the robot
dxHandler.setDeviceName("/dev/ttyUSB0");
dxHandler.setProtocolVersion(2.0);
dxHandler.openPort();
dxHandler.setBaudRate(1000000);
dxHandler.enableTorque(true);
//creation of the node
ros::init(argc, argv, "poppy_ros");
ros::NodeHandle nh;
//Publisher
ros::Publisher poppyPublisher=
nh.advertise<geometry_msgs::Twist>("joint_position",1);
ros::Rate loopRate(10);
//Suscriber
ros::Subscriber poppySuscriber=
nh.subscribe("joint_cmd",10,driverCallback);
while(ros::ok())
{
std::vector<uint16_t> _currentJointPosition;
dxHandler.readCurrentJointPosition(_currentJointPosition);
geometry_msgs::Twist value;
value.linear.x = _currentJointPosition[0];
value.linear.y = _currentJointPosition[1];
value.linear.z = _currentJointPosition[2];
value.angular.x = _currentJointPosition[3];
value.angular.y = _currentJointPosition[4];
value.angular.z = _currentJointPosition[5];
poppyPublisher.publish(value);
ros::spinOnce;
loopRate.sleep();
dxHandler.closePort();
}
return 0;
}

1
src/toolkit-dynamixel Submodule

@ -0,0 +1 @@
Subproject commit 94e8849aa1dce1c20b6ef1d0245d06a765cccaca

@ -0,0 +1 @@
Subproject commit e1f43f40ba62381baa2ce328c3dfe910ecf75a30

5
srv/ik.srv Normal file
View File

@ -0,0 +1,5 @@
geometry_msgs/Twist world_pos
---
geometry_msgs/Twist joint_pos