diff --git a/rTLTPillar/CMakeLists.txt b/rTLTPillar/CMakeLists.txt new file mode 100644 index 0000000..243e9c8 --- /dev/null +++ b/rTLTPillar/CMakeLists.txt @@ -0,0 +1,203 @@ +cmake_minimum_required(VERSION 2.8.3) +project(rTLTPillar) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## 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 + sensor_msgs + tf + urdf +) + +## 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 +# ) + +## 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 +# sensor_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 rTLTPillar +# CATKIN_DEPENDS sensor_msgs tf urdf +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/rTLTPillar.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/rTLTPillar_node.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} +# ) + +############# +## 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 +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_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_rTLTPillar.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) +add_executable(TFTLT src/TFTLT.cpp) + target_link_libraries(TFTLT ${catkin_LIBRARIES}) +add_executable(parser src/parser.cpp) + target_link_libraries(parser ${catkin_LIBRARIES}) diff --git a/rTLTPillar/launch/launch.launch b/rTLTPillar/launch/launch.launch new file mode 100644 index 0000000..3bd46eb --- /dev/null +++ b/rTLTPillar/launch/launch.launch @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/rTLTPillar/meshes/SCU.stl b/rTLTPillar/meshes/SCU.stl new file mode 100644 index 0000000..fdfb26f Binary files /dev/null and b/rTLTPillar/meshes/SCU.stl differ diff --git a/rTLTPillar/meshes/TLTBB.stl b/rTLTPillar/meshes/TLTBB.stl new file mode 100644 index 0000000..e37de67 Binary files /dev/null and b/rTLTPillar/meshes/TLTBB.stl differ diff --git a/rTLTPillar/meshes/TLTMB.stl b/rTLTPillar/meshes/TLTMB.stl new file mode 100644 index 0000000..ec1a8e0 Binary files /dev/null and b/rTLTPillar/meshes/TLTMB.stl differ diff --git a/rTLTPillar/meshes/TLTUB.stl b/rTLTPillar/meshes/TLTUB.stl new file mode 100644 index 0000000..6086c0a Binary files /dev/null and b/rTLTPillar/meshes/TLTUB.stl differ diff --git a/rTLTPillar/package.xml b/rTLTPillar/package.xml new file mode 100644 index 0000000..e9c178f --- /dev/null +++ b/rTLTPillar/package.xml @@ -0,0 +1,68 @@ + + + rTLTPillar + 0.0.0 + The rTLTPillar package + + + + + fernando + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + sensors_msgs + tf + urdf + sensors_msgs + tf + urdf + sensors_msgs + tf + urdf + + + + + + + + diff --git a/rTLTPillar/src/TFTLT b/rTLTPillar/src/TFTLT new file mode 100644 index 0000000..9707bf1 --- /dev/null +++ b/rTLTPillar/src/TFTLT @@ -0,0 +1,60 @@ +#include +#include +#include +#include + +int main(int argc, char** argv) { +ros::init(argc, argv, "myRobot_move_joint"); +ros::NodeHandle n; +ros::Publisher joint_pub = n.advertise("joint_states", 1); +tf::TransformBroadcaster broadcaster; +ros::Rate loop_rate(30); + +const double degree = M_PI/180; +double rot4 = 90; + +geometry_msgs::TransformStamped odom_trans; +sensor_msgs::JointState joint_state; +odom_trans.header.frame_id = "odom"; +odom_trans.child_frame_id = "base_link"; + +joint_state.name.resize(7); +joint_state.position.resize(7); +joint_state.name[0] ="base_to_left_link1"; +joint_state.name[1] ="left_link1_to_left_link2"; +joint_state.name[2] ="left_link2_to_left_link3"; +joint_state.name[3] ="left_link3_to_left_link4"; +joint_state.name[4] ="left_link4_to_left_link5"; +joint_state.name[5] ="left_link5_to_left_link6"; +joint_state.name[6] ="left_link6_to_left_link7"; + +while (ros::ok()) { + //update joint_state + joint_state.header.stamp = ros::Time::now(); + joint_state.position[0] = 0; + joint_state.position[1] = 0; + joint_state.position[2] = 0; + joint_state.position[3] = rot4*degree; + joint_state.position[4] = 0; + joint_state.position[5] = 0; + joint_state.position[6] = 0; + + // update transform + // (moving in a circle with radius=2) + odom_trans.header.stamp = ros::Time::now(); + odom_trans.transform.translation.x = 0; + odom_trans.transform.translation.y = 0; + odom_trans.transform.translation.z = 0; + odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(0); + + //send the joint state and transform + joint_pub.publish(joint_state); + broadcaster.sendTransform(odom_trans); + + rot4 += 1; + if (rot4 > 90) rot4 = 0; + + loop_rate.sleep(); +} +return 0; +} diff --git a/rTLTPillar/src/TFTLT.cpp b/rTLTPillar/src/TFTLT.cpp new file mode 100644 index 0000000..2c497fe --- /dev/null +++ b/rTLTPillar/src/TFTLT.cpp @@ -0,0 +1,60 @@ +#include +#include +#include +#include + +int main(int argc, char** argv) { +ros::init(argc, argv, "myRobot_move_joint"); +ros::NodeHandle n; +ros::Publisher joint_pub = n.advertise("joint_states", 1); +tf::TransformBroadcaster broadcaster; +ros::Rate loop_rate(30); + +const double degree = M_PI/180; +double rot4 = 90; + +geometry_msgs::TransformStamped odom_trans[2]; +sensor_msgs::JointState joint_state; +odom_trans[0].header.frame_id = "bot"; +odom_trans[0].child_frame_id = "mid"; +odom_trans[1].header.frame_id = "mid"; +odom_trans[1].child_frame_id = "top"; + +joint_state.name.resize(2); +joint_state.position.resize(2); +joint_state.name[0] ="base_to_mid"; +joint_state.name[1] ="mid_to_top"; + + +while (ros::ok()) { + //update joint_state + joint_state.header.stamp = ros::Time::now(); + joint_state.position[0] = 0; + joint_state.position[1] = 0; + + + // update transform + // (moving in a circle with radius=2) + odom_trans[0].header.stamp = ros::Time::now(); + odom_trans[0].transform.translation.x = 0; + odom_trans[0].transform.translation.y = 0; + odom_trans[0].transform.translation.z=0; + odom_trans[0].transform.rotation = tf::createQuaternionMsgFromYaw(0); + odom_trans[1].header.stamp = ros::Time::now(); + odom_trans[1].transform.translation.x = 0; + odom_trans[1].transform.translation.y = 0; + odom_trans[1].transform.translation.z=0; + odom_trans[1].transform.rotation = tf::createQuaternionMsgFromYaw(0); + + //send the joint state and transform + // joint_pub.publish(joint_state); + broadcaster.sendTransform(odom_trans[0]); + broadcaster.sendTransform(odom_trans[1]); + + rot4 += 1; + if (rot4 > 90) rot4 = 0; + + loop_rate.sleep(); +} +return 0; +} diff --git a/rTLTPillar/src/parser.cpp b/rTLTPillar/src/parser.cpp new file mode 100644 index 0000000..5599b3f --- /dev/null +++ b/rTLTPillar/src/parser.cpp @@ -0,0 +1,23 @@ +#include +#include "ros/ros.h" + +int main(int argc, char** argv){ + ros::init(argc, argv, "my_parser"); + + if (argc != 2){ + ROS_ERROR("Need a urdf file as argument"); + return -1; + } + std::string urdf_file = argv[1]; + + urdf::Model model; + if (!model.initFile(urdf_file)){ + ROS_ERROR("Failed to parse urdf file"); + return -1; + } + while (ros::ok()){ + + } + ROS_INFO("Successfully parsed urdf file"); + return 0; +} diff --git a/rTLTPillar/urdf/TLT.urdf b/rTLTPillar/urdf/TLT.urdf new file mode 100644 index 0000000..1172f54 --- /dev/null +++ b/rTLTPillar/urdf/TLT.urdf @@ -0,0 +1,54 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/serialprueba/CMakeLists.txt b/serialprueba/CMakeLists.txt index 871729a..88546d7 100644 --- a/serialprueba/CMakeLists.txt +++ b/serialprueba/CMakeLists.txt @@ -205,3 +205,5 @@ add_executable(serial_arduino src/serial_arduino.cpp) target_link_libraries(serial_arduino ${catkin_LIBRARIES}) add_executable(sa2 src/sa2.cpp) target_link_libraries(sa2 ${catkin_LIBRARIES}) +add_executable(Velocitytester src/Velocitytester.cpp) +target_link_libraries(Velocitytester ${catkin_LIBRARIES}) diff --git a/serialprueba/src/Velocitytester.cpp b/serialprueba/src/Velocitytester.cpp new file mode 100644 index 0000000..a41b30e --- /dev/null +++ b/serialprueba/src/Velocitytester.cpp @@ -0,0 +1,163 @@ +#include +#include +#include +#include +#include +#include +#include +#include "ros/ros.h" +#include "std_msgs/String.h" +#include "std_msgs/Int32MultiArray.h" +#include "std_msgs/Int16MultiArray.h" +#include "std_msgs/Int32.h" +#include "std_msgs/Int16.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "serialprueba/MachineState.h" +#include "serialprueba/CurrPos.h" +#include "serialprueba/CurrVel.h" +#include "serialprueba/ErrorCode.h" +#include +#include + +std::vector pos[2]; +std::vector vel[2]; +bool moving; +std_msgs::Float64MultiArray sendvel; +std_msgs::Float64MultiArray upper; +std_msgs::Float64MultiArray lower; +std::ofstream myfile; +std::ofstream myfile2; + + void testveldown(){ + while (pos[0].back()>0.290 || pos[1].back()>0.290){boost::this_thread::interruption_point();} + pos[0].clear(); + vel[0].clear(); + pos[1].clear(); + vel[1].clear(); + moving=true; + boost::chrono::steady_clock::time_point start= boost::chrono::steady_clock::now(); + boost::this_thread::sleep_for(boost::chrono::seconds(1)); + while (pos[0].back()>0.090 || pos[1].back()>0.090){boost::this_thread::interruption_point();} + boost::chrono::duration timer=boost::chrono::steady_clock::now()-start; + std::cout< timer=boost::chrono::steady_clock::now()-start; + std::cout<("/TLT/des", 1); + ros::Publisher ROSPVelocityVels = nhj.advertise("/TLT/vel", 1); + + for(int16_t cnt=25;cnt<120;cnt=cnt+10){ + sendvel.data.push_back(-cnt); + sendvel.data.push_back(-cnt); + myfile<<"Probando Velocidad: -"<0.010 || pos[1].back()>0.010){ + ROSPVelocityVels.publish(lower); + boost::this_thread::sleep_for(boost::chrono::seconds(3)); + } + ROSPVelocityVels.publish(sendvel); + tester=boost::thread(testvelup); + boost::this_thread::sleep_for(boost::chrono::seconds(5)); + if(!moving){ + tester.interrupt(); + myfile<<"Didnt move \n"; + myfile2<<"0"; + }else{ + tester.join(); + } + moving=false; + sendvel.data.clear(); +} +myfile.close(); + return 0; +} diff --git a/serialprueba/src/sa2.cpp b/serialprueba/src/sa2.cpp index 8c68469..be4019c 100644 --- a/serialprueba/src/sa2.cpp +++ b/serialprueba/src/sa2.cpp @@ -8,12 +8,16 @@ #include "ros/ros.h" #include "std_msgs/String.h" #include "std_msgs/Int32MultiArray.h" +#include "std_msgs/Int16MultiArray.h" #include "std_msgs/Int32.h" +#include "std_msgs/Int16.h" #include +#include #include #include #include #include +#include #include #include #include @@ -27,10 +31,6 @@ using namespace boost::asio; -const double_t VOLTAJEREF = 5.0; -const uint16_t NUMOUTS = 16; //15 -const uint16_t NUMINS = 16; //16 -int s = 1; std::string msgio; std::queue colaRG; std::queue colaRT; @@ -48,6 +48,7 @@ std_msgs::Float64MultiArray MSGMOVED; std_msgs::Float64MultiArray ROSLdestpositionpast; boost::thread RosListHandl[2]; uint32_t ErrorCode; +const boost::float64_t coeficient = 0.3125; struct HexCharStruct { unsigned char c; @@ -96,6 +97,12 @@ std::string uint16toLEStr(uint16_t& num){ return sinteger; } +int32_t mToflank(boost::float64_t A){ + return A*1000/coeficient; +} +boost::float64_t flanktom(int32_t A){ + return A*coeficient/1000; +} //recepcion y envio a IOPort**************************************************** bool send(std::string cmd) { @@ -359,7 +366,7 @@ void REMove(int actuador,int dato){ std::string REmsg = "RE"; REmsg.append(1, actuador-1); REmsg.append(1, dato); - REmsg.append(1, 0xff); + REmsg.append(1, 0x01); std::cout << std::endl; sends(REmsg); @@ -369,20 +376,11 @@ void RSMove(int actuador){ ROS_INFO("Stopping function "+ actuador); std::string RSmsg = "RS"; RSmsg.append(1, actuador-1); - RSmsg.append(1, 0x01); + RSmsg.append(1, 0x00); actuadorRS.push(actuador); sends(RSmsg); } -void moveVelocity(int actuator,int16_t speed,int32_t positiondestiny){ - std::string Rspeed = "RT"; - Rspeed.append(1, 0x04); - Rspeed.append(1, 0x00); - Rspeed.append(1, 11+actuator); - Rspeed.append(1, 0x30); - Rspeed.append(1, speed%256); - Rspeed.append(1, speed/256); - -} //incompleted + void movetoPos(int actuador,uint16_t speed,int32_t positiondestiny){ using boost::this_thread::get_id; std::cout << boost::this_thread::get_id()<<" "<10)){}; + + while(moveDone[actuador-1]||(abs(currposition[actuador-1]-positiondestiny)>5)){ + boost::this_thread::interruption_point(); + } RSMove(actuador); } @@ -466,7 +468,6 @@ void RSGotmsg(std::string Msg){ uint mask=0; if(actuadorRS.front()==1){mask=0xff-0x40;}else if(actuadorRS.front()==2){mask=0xff-0x10;} MachineState=MachineState & mask; - std::cout<=5 and notenough) { if (msgio.substr(0, 2) == "RO") { ROGotmsg(msgio.substr(0,5)); @@ -594,10 +592,6 @@ void readbd() { RGGot6(Msg,n1,n2); } else if(colaRG.front()==7){ - // for (int xnt = 0; xnt < msgio.length(); xnt++) { - // std::cout << hex(msgio[xnt]) << " "; - // } - // std::cout << std::endl; RGGot7(Msg); } else{ROS_INFO("WTF unknown msg for RG");} @@ -631,47 +625,65 @@ void readbd() { //funciones ROSService y ROSTopic*********************************************** -void roslistener(const std_msgs::Float64MultiArray& ROSLdestposition){ - //if(ROSLdestposition>memPositions){} +void roslistenerpos(const std_msgs::Float64MultiArray& ROSLdestposition){ for(uint16_t cnt=0;cnt5 && ROSLdestposition.data[cnt]!=ROSLdestpositionpast.data[cnt]){ + if(abs(mToflank(ROSLdestposition.data[cnt])-currposition[cnt])>5){ uint mask=0; if(cnt==0){mask=0x40;}else if(cnt==1){mask=0x10;} - std::cout<memPositions[26*(1+cnt)-1]?memPositions[26*(1+cnt)-1]:ROSLdestposition.data[cnt]; + posdest[cnt]=mToflank(ROSLdestposition.data[cnt]) >memPositions[26*(1+cnt)-1]?memPositions[26*(1+cnt)-1]:mToflank(ROSLdestposition.data[cnt]) ; posdest[cnt]=posdest[cnt]("/TLT/pos", 1); + ros::Publisher ROSPPosition = nh.advertise("/TLT/pos", 1); + ros::Publisher ROSPVelocity = nh.advertise("/TLT/currvel", 1); ros::ServiceServer service = nh.advertiseService( "/MachineState",MachineStateSRV); ros::ServiceServer service2 = nh.advertiseService("/CurrPos", CurrPosSRV); ros::ServiceServer service3 = nh.advertiseService("/CurrVel", CurrVelSRV); ros::ServiceServer service4 = nh.advertiseService("/ErrorCode", ErrorCodeSRV); - ros::Subscriber ROSLPosition = nh.subscribe("/TLT/dest", 1, roslistener); + ros::Subscriber ROSLPosition = nh.subscribe("/TLT/dest", 1, roslistenerpos); + ros::Subscriber ROSLVelocity = nh.subscribe("/TLT/vel", 1, roslistenervel); tf::TransformBroadcaster broadcaster; ros::Rate loop_rate(1); //100 @@ -863,14 +871,15 @@ void Movepruebas() { ros::init(argc, argv, "listener"); geometry_msgs::TransformStamped tfTLT[2]; - tfTLT[0].header.frame_id = "bot"; + tfTLT[0].header.frame_id = "base_link"; tfTLT[0].child_frame_id = "mid"; tfTLT[1].header.frame_id = "mid"; tfTLT[1].child_frame_id = "top"; std_msgs::String msg; - std_msgs::Int32MultiArray msg_v; + std_msgs::Float64MultiArray msg_v; + std_msgs::Float64MultiArray msg_p; std::string rot; @@ -899,7 +908,7 @@ void Movepruebas() { boost::thread t4(holdervoid,RGactuatorFinishS); boost::thread t5(holdervoid,RGlastErrorCode); boost::thread t6(holdervoid,RGactuatorSpeedS); - boost::thread t7(rospublish,msg_v,ROSPPosition,tfTLT,broadcaster,loop_rate); + boost::thread t7(rospublish,msg_v,ROSPPosition,msg_p,ROSPVelocity,tfTLT,broadcaster,loop_rate); boost::thread t8(roslistenerinit,ROSLPosition); t1.join();