cleaning
This commit is contained in:
parent
2af772c095
commit
3f3e4068f6
|
|
@ -0,0 +1,241 @@
|
||||||
|
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
|
||||||
|
rospy
|
||||||
|
std_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
|
||||||
|
# Service1.srv
|
||||||
|
# Service2.srv
|
||||||
|
# )
|
||||||
|
#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
|
||||||
|
# )
|
||||||
|
#generate_messages(
|
||||||
|
# DEPENDENCIES
|
||||||
|
# std_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 rospy std_msgs
|
||||||
|
#DEPENDS system_lib
|
||||||
|
)
|
||||||
|
|
||||||
|
###########
|
||||||
|
## Build ##
|
||||||
|
###########
|
||||||
|
|
||||||
|
## Specify additional locations of header files
|
||||||
|
## Your package locations should be listed before other locations
|
||||||
|
include_directories(
|
||||||
|
/home/lucas/toolkit-dynamixel/include
|
||||||
|
/home/lucas/toolkit-kinematics/include
|
||||||
|
/home/lucas/toolkit-dynamixel
|
||||||
|
/home/lucas/toolkit-kinematics
|
||||||
|
${OpenCV_INCLUDE_DIRS}
|
||||||
|
/home/lucas/eigen/Eigen/include
|
||||||
|
/home/lucas/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(${PROJECT_NAME}_node src/poppy_ros_node.cpp)
|
||||||
|
add_executable(poppy_ros src/poppy_ros.cpp /home/lucas/toolkit-dynamixel/src/DynamixelHandler.cpp)
|
||||||
|
add_executable(poppy_test src/poppy_test.cpp)
|
||||||
|
add_executable(poppy_pong_iv src/poppy_pong_iv.cpp)
|
||||||
|
add_executable(poppy_track_x src/poppy_track_x.cpp)
|
||||||
|
|
||||||
|
#add_executable(ik_server src/ik_server.cpp /home/lucas/toolkit-kinematics/src/Kinematics.cpp /home/lucas/toolkit-kinematics/src/RotationMatrix.cpp /home/lucas/toolkit-kinematics/src/TranslationMatrix.cpp /home/lucas/toolkit-kinematics/src/TransformationMatrix.cpp)
|
||||||
|
|
||||||
|
#add_executable(ik_client src/ik_client.cpp)
|
||||||
|
|
||||||
|
add_executable(sim_poppy_joint src/sim_poppy_joint.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_ros dxl_x64_cpp rt ${catkin_LIBRARIES})
|
||||||
|
target_link_libraries(poppy_test ${catkin_LIBRARIES})
|
||||||
|
target_link_libraries(poppy_pong_iv ${catkin_LIBRARIES})
|
||||||
|
target_link_libraries(poppy_track_x ${catkin_LIBRARIES})
|
||||||
|
|
||||||
|
#target_link_libraries(ik_server ${catkin_LIBRARIES} ${OpenCV_LIBS})
|
||||||
|
|
||||||
|
#target_link_libraries(ik_client ${catkin_LIBRARIES})
|
||||||
|
target_link_libraries(sim_poppy_joint ${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)
|
||||||
|
|
@ -0,0 +1,68 @@
|
||||||
|
<?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="lucas@todo.todo">lucas</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>rospy</build_depend>
|
||||||
|
<build_depend>std_msgs</build_depend>
|
||||||
|
<build_export_depend>roscpp</build_export_depend>
|
||||||
|
<build_export_depend>rospy</build_export_depend>
|
||||||
|
<build_export_depend>std_msgs</build_export_depend>
|
||||||
|
<exec_depend>roscpp</exec_depend>
|
||||||
|
<exec_depend>rospy</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>
|
||||||
|
|
@ -0,0 +1,12 @@
|
||||||
|
<!-- poppy_launch.launch -->
|
||||||
|
<launch>
|
||||||
|
<!-- Launch poppy_ros -->
|
||||||
|
<!--include file="$(find poppy_ros)/poppy_ros.launch" /-->
|
||||||
|
|
||||||
|
<!-- Launch poppy_pong_iv -->
|
||||||
|
<node name="poppy_ik" pkg="poppy_ros" type="poppy_pong_iv" />
|
||||||
|
|
||||||
|
<!-- Launch poppy_ros -->
|
||||||
|
<node name="poppy_ros" pkg="poppy_ros" type="poppy_ros" />
|
||||||
|
</launch>
|
||||||
|
|
||||||
|
|
@ -0,0 +1,99 @@
|
||||||
|
#include "ros/ros.h"
|
||||||
|
#include "geometry_msgs/Twist.h"
|
||||||
|
#include "geometry_msgs/Point.h"
|
||||||
|
#include <std_msgs/MultiArrayLayout.h>
|
||||||
|
#include <std_msgs/MultiArrayDimension.h>
|
||||||
|
#include <std_msgs/Float32MultiArray.h>
|
||||||
|
#include <array> // Inclure la bibliothèque std::array pour déclarer des tableaux statiques
|
||||||
|
#include <cmath> // Inclure la bibliothèque cmath pour atan2
|
||||||
|
|
||||||
|
// Global variables
|
||||||
|
float _fps = 10.0f; // Hz
|
||||||
|
int _nbJoints = 6;
|
||||||
|
float _minJointCmd = 0;
|
||||||
|
float _maxJointCmd = 1023;
|
||||||
|
float _minJointAngle = -180.0f;
|
||||||
|
float _maxJointAngle = 180.0f;
|
||||||
|
float L1 = 65;
|
||||||
|
float L2 = 55;
|
||||||
|
float angleBase = 100;
|
||||||
|
bool hitting_need = false;
|
||||||
|
ros::Publisher _jointPositionPublisher;
|
||||||
|
|
||||||
|
float get_q2(float x, float y)
|
||||||
|
{
|
||||||
|
float q2; // Déclarer un tableau statique de 2 éléments de type float
|
||||||
|
q2 = acos((x * x + y * y - L1 * L1 - L2 * L2) / (2 * L1 * L2));
|
||||||
|
|
||||||
|
return q2;
|
||||||
|
}
|
||||||
|
|
||||||
|
float get_q1(float x, float y)
|
||||||
|
{
|
||||||
|
float q1;
|
||||||
|
float q2 = get_q2(x, y);
|
||||||
|
|
||||||
|
q1 = atan2(y, x) - atan2(L2 * sin(q2), L1 + L2 * cos(q2));
|
||||||
|
|
||||||
|
return q1;
|
||||||
|
}
|
||||||
|
|
||||||
|
void posCMDCallback(const geometry_msgs::Point& joint_pos)
|
||||||
|
{
|
||||||
|
if (sqrt(pow(joint_pos.x, 2) + pow(joint_pos.y, 2)) <= 120)
|
||||||
|
{
|
||||||
|
if (hitting_need == true)
|
||||||
|
{
|
||||||
|
joint_pos.x += 20;
|
||||||
|
joint_pos.y += 20;
|
||||||
|
}
|
||||||
|
geometry_msgs::Twist joint_cmd;
|
||||||
|
float q1 = get_q1(joint_pos.x, joint_pos.y);
|
||||||
|
float q2 = get_q2(joint_pos.x, joint_pos.y);
|
||||||
|
// stores them into a msg
|
||||||
|
joint_cmd.linear.x = q1*(180.0f/3.141592f);
|
||||||
|
joint_cmd.linear.y = angleBase;
|
||||||
|
joint_cmd.linear.z = q2*(180.0f/3.141592f);
|
||||||
|
joint_cmd.angular.x = (-q1-q2)*(180.0f/3.141592f); // end-effector orientation
|
||||||
|
|
||||||
|
// publish the Twist message to the joint_position topic
|
||||||
|
_jointPositionPublisher.publish(joint_cmd);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void hittingCommand(const geometry_msgs::Point& trigger_signal) {
|
||||||
|
hitting_need = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(int argc, char** argv)
|
||||||
|
{
|
||||||
|
// create a node called poppy_ik
|
||||||
|
ros::init(argc, argv, "poppy_ik");
|
||||||
|
|
||||||
|
// create a node handle
|
||||||
|
ros::NodeHandle nh;
|
||||||
|
|
||||||
|
// create a publisher to joint_cmd topic
|
||||||
|
_jointPositionPublisher = nh.advertise<geometry_msgs::Twist>("joint_cmd", 1);
|
||||||
|
// create a subscriber to position_cmd
|
||||||
|
ros::Subscriber sub = nh.subscribe("position_cmd", 1, posCMDCallback);
|
||||||
|
ros::Subscriber sub_trigger = nh.subscribe("trigger", 1, hittingCommand);
|
||||||
|
|
||||||
|
// create a loop rate
|
||||||
|
ros::Rate loopRate(_fps);
|
||||||
|
|
||||||
|
|
||||||
|
ROS_INFO("===Launching Poppy node===");
|
||||||
|
|
||||||
|
// loop until Ctrl+C is pressed or ROS connectivity issues
|
||||||
|
while(ros::ok())
|
||||||
|
{
|
||||||
|
// 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();
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
@ -0,0 +1,107 @@
|
||||||
|
#include "ros/ros.h"
|
||||||
|
#include "geometry_msgs/Twist.h"
|
||||||
|
#include "DynamixelHandler.h"
|
||||||
|
|
||||||
|
// 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;
|
||||||
|
// create vector unit 16_t
|
||||||
|
std::vector<uint16_t> jointVec;
|
||||||
|
|
||||||
|
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 jointCMDCallback(const geometry_msgs::Twist& joint_cmd)
|
||||||
|
{
|
||||||
|
jointVec.clear();
|
||||||
|
//fill it w joint_cmd_values
|
||||||
|
jointVec.push_back(convertAnglesToJointCmd(joint_cmd.linear.x));
|
||||||
|
jointVec.push_back(convertAnglesToJointCmd(joint_cmd.linear.y));
|
||||||
|
jointVec.push_back(convertAnglesToJointCmd(joint_cmd.linear.z));
|
||||||
|
jointVec.push_back(convertAnglesToJointCmd(joint_cmd.angular.x));
|
||||||
|
jointVec.push_back(0.0);
|
||||||
|
jointVec.push_back(0.0);
|
||||||
|
//call sendTargetJOintPosition(vector) of DxlHandler
|
||||||
|
_oDxlHandler.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<geometry_msgs::Twist>("joint_position", 1);
|
||||||
|
|
||||||
|
//create a subscriber
|
||||||
|
ros::Subscriber sub = nh.subscribe("joint_cmd",1, jointCMDCallback);
|
||||||
|
|
||||||
|
// 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<uint16_t> 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];
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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;
|
||||||
|
}
|
||||||
|
|
@ -0,0 +1,60 @@
|
||||||
|
#include "ros/ros.h"
|
||||||
|
#include "geometry_msgs/Twist.h"
|
||||||
|
|
||||||
|
|
||||||
|
ros::Publisher _jointPositionPublisher;
|
||||||
|
|
||||||
|
int main(int argc, char** argv)
|
||||||
|
{
|
||||||
|
// create a node called poppy_ros
|
||||||
|
ros::init(argc, argv, "poppy_ros_test");
|
||||||
|
//ros::init(argc, argv, "autopilot");
|
||||||
|
|
||||||
|
// create a node handle
|
||||||
|
ros::NodeHandle nh;
|
||||||
|
|
||||||
|
// create a publisher to joint_position topic
|
||||||
|
_jointPositionPublisher = nh.advertise<geometry_msgs::Twist>("joint_cmd", 1);
|
||||||
|
|
||||||
|
|
||||||
|
// create a loop rate
|
||||||
|
ros::Rate loopRate(1);
|
||||||
|
|
||||||
|
// create a Twist message
|
||||||
|
geometry_msgs::Twist jointPositionMsg;
|
||||||
|
|
||||||
|
|
||||||
|
int x=0;
|
||||||
|
|
||||||
|
ROS_INFO("===Launching Poppy node===");
|
||||||
|
|
||||||
|
// loop until Ctrl+C is pressed or ROS connectivity issues
|
||||||
|
while(ros::ok())
|
||||||
|
{
|
||||||
|
|
||||||
|
// stores them into a msg
|
||||||
|
if (x != 180)
|
||||||
|
{
|
||||||
|
jointPositionMsg.linear.x = x;
|
||||||
|
jointPositionMsg.linear.y = 100;
|
||||||
|
jointPositionMsg.linear.z = x;
|
||||||
|
jointPositionMsg.angular.x = x;
|
||||||
|
x+=10;
|
||||||
|
}
|
||||||
|
else if(x==180)
|
||||||
|
{
|
||||||
|
x=0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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();
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
@ -0,0 +1,62 @@
|
||||||
|
#include "ros/ros.h"
|
||||||
|
#include "geometry_msgs/Twist.h"
|
||||||
|
#include "geometry_msgs/Point.h"
|
||||||
|
#include <std_msgs/MultiArrayLayout.h>
|
||||||
|
#include <std_msgs/MultiArrayDimension.h>
|
||||||
|
#include <std_msgs/Float32MultiArray.h>
|
||||||
|
#include <array> // Inclure la bibliothèque std::array pour déclarer des tableaux statiques
|
||||||
|
#include <cmath> // Inclure la bibliothèque cmath pour atan2
|
||||||
|
|
||||||
|
|
||||||
|
// Global variables
|
||||||
|
float _fps = 10.0f; // Hz
|
||||||
|
ros::Publisher _jointPositionPublisher;
|
||||||
|
float std_pos = 65.0f;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void posCMDCallback(const geometry_msgs::Point& ballPos)
|
||||||
|
{
|
||||||
|
geometry_msgs::Point joint_pos;
|
||||||
|
// stores them into a msg
|
||||||
|
joint_pos.x = std_pos;
|
||||||
|
joint_pos.y = ballPos.y;
|
||||||
|
|
||||||
|
// publish the Twist message to the joint_position topic
|
||||||
|
_jointPositionPublisher.publish(joint_pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(int argc, char** argv)
|
||||||
|
{
|
||||||
|
//ros::init(argc, argv, "autopilot");
|
||||||
|
// create a node called poppy_ros
|
||||||
|
ros::init(argc, argv, "poppy_track_ball");
|
||||||
|
|
||||||
|
// create a node handle
|
||||||
|
ros::NodeHandle nh;
|
||||||
|
|
||||||
|
// create a publisher to joint_position topic
|
||||||
|
_jointPositionPublisher = nh.advertise<geometry_msgs::Point>("position_cmd", 1);
|
||||||
|
//create a subscriber
|
||||||
|
ros::Subscriber sub = nh.subscribe("ball_coordinates",1, posCMDCallback);
|
||||||
|
|
||||||
|
// create a loop rate
|
||||||
|
ros::Rate loopRate(_fps);
|
||||||
|
|
||||||
|
ROS_INFO("===Launching Poppy node===");
|
||||||
|
|
||||||
|
// loop until Ctrl+C is pressed or ROS connectivity issues
|
||||||
|
while(ros::ok())
|
||||||
|
{
|
||||||
|
|
||||||
|
// 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();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
@ -0,0 +1,53 @@
|
||||||
|
#include "ros/ros.h"
|
||||||
|
#include "geometry_msgs/Twist.h"
|
||||||
|
#include "sensor_msgs/JointState.h"
|
||||||
|
|
||||||
|
std::vector<double> jointVec;
|
||||||
|
void jointCMDCallback(const geometry_msgs::Twist& joint_cmd)
|
||||||
|
{
|
||||||
|
jointVec.clear();
|
||||||
|
//fill it w joint_cmd_values
|
||||||
|
jointVec.push_back(joint_cmd.linear.x);
|
||||||
|
jointVec.push_back(joint_cmd.linear.y);
|
||||||
|
jointVec.push_back(joint_cmd.linear.z);
|
||||||
|
jointVec.push_back(joint_cmd.angular.x);
|
||||||
|
jointVec.push_back(joint_cmd.angular.y);
|
||||||
|
jointVec.push_back(joint_cmd.angular.z);
|
||||||
|
}
|
||||||
|
double deg2rad(double angle)
|
||||||
|
{
|
||||||
|
return -angle / 180.0 * M_PI;
|
||||||
|
}
|
||||||
|
int main(int argc, char** argv)
|
||||||
|
{
|
||||||
|
ros::init(argc, argv, "poppy_ros", ros::init_options::NoSigintHandler);
|
||||||
|
|
||||||
|
// create a node handle
|
||||||
|
ros::NodeHandle nh;
|
||||||
|
|
||||||
|
|
||||||
|
//create a subscriber
|
||||||
|
ros::Subscriber sub = nh.subscribe("joint_cmd",1, jointCMDCallback);
|
||||||
|
|
||||||
|
// create a loop rate
|
||||||
|
ros::Rate loopRate(10);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
ROS_INFO("===Launching Poppy node 2===");
|
||||||
|
ros::Publisher jointCmdPublisher = nh.advertise<sensor_msgs::JointState>("joint_states", 1);
|
||||||
|
std::vector<std::string> jointCmdNameArray = {"m1", "m2", "m3", "m4", "m5", "m6"};
|
||||||
|
while (ros::ok())
|
||||||
|
{
|
||||||
|
sensor_msgs::JointState jointCmdMsg;
|
||||||
|
jointCmdMsg.header.stamp = ros::Time::now();
|
||||||
|
jointCmdMsg.header.seq++;
|
||||||
|
jointCmdMsg.position = jointVec;
|
||||||
|
jointCmdMsg.name = jointCmdNameArray;
|
||||||
|
jointCmdPublisher.publish(jointCmdMsg);
|
||||||
|
ROS_INFO("===data published===");
|
||||||
|
ros::spinOnce();
|
||||||
|
loopRate.sleep();
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
Loading…
Reference in New Issue