diff --git a/Finddarwin_leg_kinematics.cmake b/Finddarwin_leg_kinematics.cmake new file mode 100755 index 0000000000000000000000000000000000000000..928ba4926f51af7e3ce7471f2b97a32271ec4725 --- /dev/null +++ b/Finddarwin_leg_kinematics.cmake @@ -0,0 +1,21 @@ +#edit the following line to add the librarie's header files +FIND_PATH(darwin_leg_kinematics_INCLUDE_DIR darwin_leg_kinematics.h /usr/include/iridrivers /usr/local/include/iridrivers) + +FIND_LIBRARY(darwin_leg_kinematics_LIBRARY + NAMES darwin_leg_kinematics + PATHS /usr/lib /usr/local/lib /usr/local/lib/iridrivers) + +IF (darwin_leg_kinematics_INCLUDE_DIR AND darwin_leg_kinematics_LIBRARY) + SET(darwin_leg_kinematics_FOUND TRUE) +ENDIF (darwin_leg_kinematics_INCLUDE_DIR AND darwin_leg_kinematics_LIBRARY) + +IF (darwin_leg_kinematics_FOUND) + IF (NOT darwin_leg_kinematics_FIND_QUIETLY) + MESSAGE(STATUS "Found darwin_leg_kinematics: ${darwin_leg_kinematics_LIBRARY}") + ENDIF (NOT darwin_leg_kinematics_FIND_QUIETLY) +ELSE (darwin_leg_kinematics_FOUND) + IF (darwin_leg_kinematics_FIND_REQUIRED) + MESSAGE(FATAL_ERROR "Could not find darwin_leg_kinematics") + ENDIF (darwin_leg_kinematics_FIND_REQUIRED) +ENDIF (darwin_leg_kinematics_FOUND) + diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 8e1d04e725b895a4628830e40aa0c1be96075af4..f368578b842695763a3d291392553dba3c396006 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -17,20 +17,30 @@ SET(robot_sources darwin_robot.cpp darwin_robot_exceptions.cpp) # application header files SET(robot_headers darwin_robot.h darwin_robot_exceptions.h) +# locate the necessary dependencies +FIND_PACKAGE(iriutils REQUIRED) +FIND_PACKAGE(dynamixel REQUIRED) +FIND_PACKAGE(Eigen3 REQUIRED) + IF(KDL_FOUND) # driver source files - SET(kin_sources darwin_arm_kinematics.cpp darwin_robot_exceptions.cpp) + SET(kin_arm_sources darwin_arm_kinematics.cpp darwin_robot_exceptions.cpp) # application header files - SET(kin_headers darwin_arm_kinematics.h darwin_robot_exceptions.h) + SET(kin_arm_headers darwin_arm_kinematics.h darwin_robot_exceptions.h) ENDIF(KDL_FOUND) -# locate the necessary dependencies -FIND_PACKAGE(iriutils REQUIRED) -FIND_PACKAGE(dynamixel REQUIRED) +IF(EIGEN3_FOUND) + # driver source files + SET(kin_leg_sources darwin_leg_kinematics.cpp darwin_robot_exceptions.cpp) + # application header files + SET(kin_leg_headers darwin_leg_kinematics.h darwin_robot_exceptions.h) +ENDIF(EIGEN3_FOUND) + # add the necessary include directories INCLUDE_DIRECTORIES(.) INCLUDE_DIRECTORIES(${iriutils_INCLUDE_DIR}) INCLUDE_DIRECTORIES(${dynamixel_INCLUDE_DIR}) +INCLUDE_DIRECTORIES(${EIGEN3_INCLUDE_DIR}) INCLUDE_DIRECTORIES(${DARWIN_FW_PATH}/include) # create the shared library ADD_LIBRARY(darwin_robot SHARED ${robot_sources} ${XSD_SOURCES}) @@ -41,7 +51,7 @@ TARGET_LINK_LIBRARIES(darwin_robot ${dynamixel_LIBRARY}) TARGET_LINK_LIBRARIES(darwin_robot ${XSD_LIBRARY}) IF(KDL_FOUND) - ADD_LIBRARY(darwin_arm_kinematics SHARED ${kin_sources} ${XSD_SOURCES}) + ADD_LIBRARY(darwin_arm_kinematics SHARED ${kin_arm_sources} ${XSD_SOURCES}) ADD_DEPENDENCIES(darwin_arm_kinematics xsd_files_gen) # link necessary libraries TARGET_LINK_LIBRARIES(darwin_arm_kinematics ${iriutils_LIBRARY}) @@ -49,6 +59,14 @@ IF(KDL_FOUND) TARGET_LINK_LIBRARIES(darwin_arm_kinematics ${KDL_LIBS}) ENDIF(KDL_FOUND) +IF(EIGEN3_FOUND) + ADD_LIBRARY(darwin_leg_kinematics SHARED ${kin_leg_sources} ${XSD_SOURCES}) + ADD_DEPENDENCIES(darwin_leg_kinematics xsd_files_gen) + # link necessary libraries + TARGET_LINK_LIBRARIES(darwin_leg_kinematics ${iriutils_LIBRARY}) + TARGET_LINK_LIBRARIES(darwin_leg_kinematics ${XSD_LIBRARY}) +ENDIF(EIGEN3_FOUND) + SET_SOURCE_FILES_PROPERTIES(${XSD_SOURCES} PROPERTIES GENERATED 1) INSTALL(TARGETS darwin_robot @@ -59,12 +77,20 @@ INSTALL(FILES ${robot_headers} DESTINATION include/iridrivers) INSTALL(FILES ${DARWIN_FW_PATH}/include/darwin_registers.h DESTINATION include/iridrivers) INSTALL(FILES ${DARWIN_FW_PATH}/include/action_id.h DESTINATION include/iridrivers) IF(KDL_FOUND) - INSTALL(FILES ${kin_heders} DESTINATION include/iridrivers) + INSTALL(FILES ${kin_arm_heders} DESTINATION include/iridrivers) INSTALL(TARGETS darwin_arm_kinematics RUNTIME DESTINATION bin LIBRARY DESTINATION lib/iridrivers ARCHIVE DESTINATION lib/iridrivers) + INSTALL(FILES ../Finddarwin_arm_kinematics.cmake DESTINATION ${CMAKE_ROOT}/Modules/) ENDIF(KDL_FOUND) +IF(EIGEN3_FOUND) + INSTALL(FILES ${kin_leg_heders} DESTINATION include/iridrivers) + INSTALL(TARGETS darwin_leg_kinematics + RUNTIME DESTINATION bin + LIBRARY DESTINATION lib/iridrivers + ARCHIVE DESTINATION lib/iridrivers) + INSTALL(FILES ../Finddarwin_leg_kinematics.cmake DESTINATION ${CMAKE_ROOT}/Modules/) +ENDIF(EIGEN3_FOUND) INSTALL(FILES ../Finddarwin_robot.cmake DESTINATION ${CMAKE_ROOT}/Modules/) -INSTALL(FILES ../Finddarwin_arm_kinematics.cmake DESTINATION ${CMAKE_ROOT}/Modules/) ADD_SUBDIRECTORY(examples) diff --git a/src/darwin_arm_kinematics.cpp b/src/darwin_arm_kinematics.cpp index 8b66356ce758616dd28f963cc9a9d7e72df9d019..b298dc97579cdff3497fe2183fb562651b1fbdd8 100644 --- a/src/darwin_arm_kinematics.cpp +++ b/src/darwin_arm_kinematics.cpp @@ -6,7 +6,7 @@ #include <stdlib.h> #include <time.h> #ifdef _HAVE_XSD -#include "xml/darwin_arm_kin.hxx" +#include "xml/darwin_kin_chain.hxx" #endif CDarwinArmKinematics::CDarwinArmKinematics() @@ -39,7 +39,7 @@ void CDarwinArmKinematics::load_chain(std::string &filename) if(stat(filename.c_str(),&buffer)==0) { try{ - std::auto_ptr<joints_t> chain(darwin_arm_chain(filename.c_str(), xml_schema::flags::dont_validate)); + std::auto_ptr<joints_t> chain(darwin_kin_chain(filename.c_str(), xml_schema::flags::dont_validate)); extra=6-chain->joint().size(); if(extra<0) extra=0; this->q_max.resize(6); diff --git a/src/darwin_leg_kinematics.cpp b/src/darwin_leg_kinematics.cpp new file mode 100644 index 0000000000000000000000000000000000000000..4a55817a6b76ba403fdfce5fe8f7ae8edcdd5e24 --- /dev/null +++ b/src/darwin_leg_kinematics.cpp @@ -0,0 +1,127 @@ +#include "darwin_leg_kinematics.h" +#include "darwin_robot_exceptions.h" +#include <sys/types.h> +#include <sys/stat.h> +#include <unistd.h> +#include <stdlib.h> +#include <time.h> +#include <math.h> +#ifdef _HAVE_XSD +#include "xml/darwin_kin_chain.hxx" +#endif + +CDarwinLegKinematics::CDarwinLegKinematics() +{ + srand(time(NULL)); + this->num_dof=0; + this->fw_kin_transforms.clear(); + this->fw_kin_params.clear(); +} + +double CDarwinLegKinematics::angle_norm(double angle) +{ + while(fabs(angle)>1.5707) + { + if(angle>0) angle-=1.5707; + if(angle<0) angle+=1.5707; + } + + return angle; +} + +void CDarwinLegKinematics::load_chain(std::string &filename) +{ + joints_t::joint_iterator iterator; + Eigen::Matrix4d transform; + struct stat buffer; + TDHParams params; + unsigned int i=0; + + if(stat(filename.c_str(),&buffer)==0) + { + try{ + std::auto_ptr<joints_t> chain(darwin_kin_chain(filename.c_str(), xml_schema::flags::dont_validate)); + this->fw_kin_params.clear(); + this->fw_kin_transforms.clear(); + this->num_dof=0; + for(iterator=chain->joint().begin(),i=0;iterator!=chain->joint().end();iterator++,i++) + { + params.alpha=iterator->params().alpha(); + params.a=iterator->params().a(); + params.d=iterator->params().d(); + params.theta=iterator->params().theta(); + this->fw_kin_params.push_back(params); + // precompute the transforms + transform(2,0)=0.0; + transform(2,1)=sin(params.alpha); + transform(2,2)=cos(params.alpha); + transform(2,3)=params.d; + transform(3,0)=0.0; + transform(3,1)=0.0; + transform(3,2)=0.0; + transform(3,3)=1.0; + this->fw_kin_transforms.push_back(transform); + this->num_dof++; + } + }catch(const xml_schema::exception& e){ + std::ostringstream os; + os << e; + throw CDarwinRobotException(_HERE_,os.str()); + } + } + else + throw CDarwinRobotException(_HERE_,"Leg chain definition file does not exist"); +} + +void CDarwinLegKinematics::get_forward_kinematics(std::vector<double> &angles,std::vector<double> &pos,std::vector<double> &rot) +{ + unsigned int i=0; + Eigen::Matrix4d total_transform=Eigen::Matrix4d::Identity(); + + if(angles.size()!=this->num_dof) + throw CDarwinRobotException(_HERE_,"Invalid angle vector size"); + else + { + for(i=0;i<this->num_dof;i++) + { + this->fw_kin_transforms[i](0,0)=cos(angles[i]+this->fw_kin_params[i].theta); + this->fw_kin_transforms[i](0,1)=-sin(angles[i]+this->fw_kin_params[i].theta)*cos(this->fw_kin_params[i].alpha); + this->fw_kin_transforms[i](0,2)=sin(angles[i]+this->fw_kin_params[i].theta)*sin(this->fw_kin_params[i].alpha); + this->fw_kin_transforms[i](0,3)=this->fw_kin_params[i].a*cos(angles[i]+this->fw_kin_params[i].theta); + this->fw_kin_transforms[i](1,0)=sin(angles[i]+this->fw_kin_params[i].theta); + this->fw_kin_transforms[i](1,1)=cos(angles[i]+this->fw_kin_params[i].theta)*cos(this->fw_kin_params[i].alpha); + this->fw_kin_transforms[i](1,2)=-cos(angles[i]+this->fw_kin_params[i].theta)*sin(this->fw_kin_params[i].alpha); + this->fw_kin_transforms[i](1,3)=this->fw_kin_params[i].a*sin(angles[i]+this->fw_kin_params[i].theta); + total_transform*=this->fw_kin_transforms[i]; + } + pos.resize(3); + pos[0]=total_transform(0,3); + pos[1]=total_transform(1,3); + pos[2]=total_transform(2,3); + rot.resize(3); + if(total_transform(0,0)==0.0 && total_transform(1,0)==0.0) + { + rot[0]=atan2(total_transform(0,1),total_transform(1,1)); + rot[1]=1.5707; + rot[2]=0.0; + } + else + { + rot[0]=atan2(total_transform(2,1),total_transform(2,2)); + rot[1]=atan2(-total_transform(2,0),sqrt(pow(total_transform(0,0),2)+pow(total_transform(1,0),2))); + rot[2]=atan2(total_transform(1,0),total_transform(0,0)); + } + } +} + +void CDarwinLegKinematics::get_inverse_kinematics(std::vector<double> &pos,std::vector<double> &rot,std::vector<double> &angles) +{ +} + +CDarwinLegKinematics::~CDarwinLegKinematics() +{ + this->num_dof=0; + this->fw_kin_transforms.clear(); + this->fw_kin_params.clear(); +} + diff --git a/src/darwin_leg_kinematics.h b/src/darwin_leg_kinematics.h new file mode 100644 index 0000000000000000000000000000000000000000..0ebcd76c1e10154fe78a75c51bdce1b95c3c4493 --- /dev/null +++ b/src/darwin_leg_kinematics.h @@ -0,0 +1,31 @@ +#ifndef _DARWIN_LEG_KINEMATICS_H +#define _DARWIN_LEG_KINEMATICS_H + +#include <string> +#include <vector> +#include <Eigen/Dense> + +typedef struct{ + double alpha; + double a; + double d; + double theta; +}TDHParams; + +class CDarwinLegKinematics +{ + private: + unsigned int num_dof; + std::vector<Eigen::Matrix4d> fw_kin_transforms; + std::vector<TDHParams> fw_kin_params; + protected: + double angle_norm(double angle); + public: + CDarwinLegKinematics(); + void load_chain(std::string &filename); + void get_forward_kinematics(std::vector<double> &angles,std::vector<double> &pos,std::vector<double> &rot); + void get_inverse_kinematics(std::vector<double> &pos,std::vector<double> &rot,std::vector<double> &angles); + ~CDarwinLegKinematics(); +}; + +#endif diff --git a/src/darwin_robot.h b/src/darwin_robot.h index 76d704310f1bc138f3be46e7917c96599f3f6974..30d3a9d168d7bf5432ab8f33b8b7060dac141cc5 100644 --- a/src/darwin_robot.h +++ b/src/darwin_robot.h @@ -34,7 +34,7 @@ typedef enum {START_PB=0,MODE_PB=1} pushbutton_t; #define ADC_NUM_CHANNELS 16 typedef enum {ADC_CH1=0,ADC_CH2=1,ADC_CH3=2,ADC_CH4=3,ADC_CH5=4,ADC_CH6=5,ADC_CH7=6,ADC_CH8=7, - ADC_CH9=8,ADC_CH10=9,ADC_CH11=10,ADC_CH12=11,ADC_CH13=12,ADC_CH14=13,ADC_CH16=15,ADC_CH18=17} adc_t; + ADC_CH9=8,ADC_CH10=9,ADC_CH12=10,ADC_CH14=11} adc_t; #define JOINTS_NUM_GROUPS 4 diff --git a/src/examples/CMakeLists.txt b/src/examples/CMakeLists.txt index 947eeb0cd09c8186a81a9822cbb0f8e8e12d08c8..a21e19c4def6a741116edbd724ad998e58260818 100644 --- a/src/examples/CMakeLists.txt +++ b/src/examples/CMakeLists.txt @@ -39,7 +39,12 @@ ADD_EXECUTABLE(darwin_head_tracking_test darwin_head_tracking_test.cpp) TARGET_LINK_LIBRARIES(darwin_head_tracking_test darwin_robot) # create an example application -#ADD_EXECUTABLE(darwin_kin darwin_kin.cpp) +ADD_EXECUTABLE(darwin_arm_kin darwin_arm_kin.cpp) # link necessary libraries -#TARGET_LINK_LIBRARIES(darwin_kin darwin_arm_kinematics) +TARGET_LINK_LIBRARIES(darwin_arm_kin darwin_arm_kinematics) + +# create an example application +ADD_EXECUTABLE(darwin_leg_kin darwin_leg_kin.cpp) +# link necessary libraries +TARGET_LINK_LIBRARIES(darwin_leg_kin darwin_leg_kinematics) diff --git a/src/examples/darwin_adc_test.cpp b/src/examples/darwin_adc_test.cpp index 7548ce3da8db13c4c1005111be58402c2b901b94..de3b241e9d1cc613b195f76e0d35479ff37794ae 100644 --- a/src/examples/darwin_adc_test.cpp +++ b/src/examples/darwin_adc_test.cpp @@ -14,7 +14,7 @@ int main(int argc, char *argv[]) CDarwinRobot darwin("Darwin",robot_device,1000000,0x02); std::cout << "found darwin controller" << std::endl; darwin.adc_start(); - for(i=0;i<50;i++) + for(i=0;i<5000;i++) { std::cout << "Temperature: " << darwin.adc_get_temperature() << std::endl; std::cout << "Vref: " << darwin.adc_get_vrefint() << std::endl; @@ -28,12 +28,8 @@ int main(int argc, char *argv[]) std::cout << "Channel8: " << darwin.adc_get_value(ADC_CH8) << std::endl; std::cout << "Channel9: " << darwin.adc_get_value(ADC_CH9) << std::endl; std::cout << "Channel10: " << darwin.adc_get_value(ADC_CH10) << std::endl; - std::cout << "Channel11: " << darwin.adc_get_value(ADC_CH11) << std::endl; std::cout << "Channel12: " << darwin.adc_get_value(ADC_CH12) << std::endl; - std::cout << "Channel13: " << darwin.adc_get_value(ADC_CH13) << std::endl; std::cout << "Channel14: " << darwin.adc_get_value(ADC_CH14) << std::endl; - std::cout << "Channel15: " << darwin.adc_get_value(ADC_CH16) << std::endl; - std::cout << "Channel16: " << darwin.adc_get_value(ADC_CH18) << std::endl; usleep(100000); } darwin.adc_stop(); diff --git a/src/examples/darwin_kin.cpp b/src/examples/darwin_arm_kin.cpp similarity index 100% rename from src/examples/darwin_kin.cpp rename to src/examples/darwin_arm_kin.cpp diff --git a/src/examples/darwin_leg_kin.cpp b/src/examples/darwin_leg_kin.cpp new file mode 100644 index 0000000000000000000000000000000000000000..c527a0b66a735fd563721e8c4fcc8d5c962f28fa --- /dev/null +++ b/src/examples/darwin_leg_kin.cpp @@ -0,0 +1,28 @@ +#include "darwin_leg_kinematics.h" +#include "darwin_robot_exceptions.h" + +#include <iostream> + +std::string kin_file="../src/xml/right_leg.xml"; + +int main(int argc, char *argv[]) +{ + std::vector<double> joints_in(6),pos,rot_out; + + try{ + CDarwinLegKinematics kin; + kin.load_chain(kin_file); + + joints_in[0]=atof(argv[1]); + joints_in[1]=atof(argv[2]); + joints_in[2]=atof(argv[3]); + joints_in[3]=atof(argv[4]); + joints_in[4]=atof(argv[5]); + joints_in[5]=atof(argv[6]); + kin.get_forward_kinematics(joints_in,pos,rot_out); + std::cout << pos[0] << "," << pos[1] << "," << pos[2] << std::endl; + + }catch(CException &e){ + std::cout << e.what() << std::endl; + } +} diff --git a/src/xml/CMakeLists.txt b/src/xml/CMakeLists.txt index 73c3ed99f4caef8cf2c7ce2d39e64bd4cb0b116e..ecf29342aa48083131d8482d2ad3eb1f0f0cf228 100644 --- a/src/xml/CMakeLists.txt +++ b/src/xml/CMakeLists.txt @@ -14,7 +14,7 @@ IF(XSD_FOUND) SET(XSD_LIBRARY ${XSD_LIBRARY} PARENT_SCOPE) SET(XSD_PATH ${CMAKE_CURRENT_SOURCE_DIR}) - SET(XSD_FILES darwin_config.xsd darwin_arm_kin.xsd) + SET(XSD_FILES darwin_config.xsd darwin_kin_chain.xsd) IF(XSD_FILES) FOREACH(xsd_file ${XSD_FILES}) diff --git a/src/xml/darwin_action.xml b/src/xml/darwin_action.xml deleted file mode 100644 index 9ab38f005552f7aeb999deb24b95aec09b652636..0000000000000000000000000000000000000000 --- a/src/xml/darwin_action.xml +++ /dev/null @@ -1,86 +0,0 @@ -<?xml version="1.0"?> - -<darwin_config xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" - xsi:noNamespaceSchemaLocation="darwin_config.xsd"> - <servo> - <name>j_shoulder_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_shoulder_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_high_arm_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_high_arm_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_low_arm_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_low_arm_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_pelvis_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_pelvis_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_thigh1_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_thigh1_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_thigh2_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_thigh2_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_tibia_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_tibia_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_ankle1_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_ankle1_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_ankle2_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_ankle2_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_pan</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_tilt</name> - <motion_module>action</motion_module> - </servo> -</darwin_config> - diff --git a/src/xml/darwin_config.xml b/src/xml/darwin_config.xml index 33f3cef45b544d5659ad9b81cf05b3c079b1eda9..ac76ac0cbf1c3e27016602ccb1f6d9c196a9cae3 100644 --- a/src/xml/darwin_config.xml +++ b/src/xml/darwin_config.xml @@ -3,75 +3,75 @@ <darwin_config xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="darwin_config.xsd"> <servo> - <name>j_shoulder_r</name> + <name>j_shoulder_pitch_r</name> <motion_module>joints</motion_module> </servo> <servo> - <name>j_shoulder_l</name> + <name>j_shoulder_pitch_l</name> <motion_module>joints</motion_module> </servo> <servo> - <name>j_high_arm_r</name> + <name>j_shoulder_roll_r</name> <motion_module>joints</motion_module> </servo> <servo> - <name>j_high_arm_l</name> + <name>j_shoulder_roll_l</name> <motion_module>joints</motion_module> </servo> <servo> - <name>j_low_arm_r</name> + <name>j_elbow_r</name> <motion_module>joints</motion_module> </servo> <servo> - <name>j_low_arm_l</name> + <name>j_elbow_l</name> <motion_module>joints</motion_module> </servo> <servo> - <name>j_pelvis_r</name> + <name>j_hip_yaw_r</name> <motion_module>walking</motion_module> </servo> <servo> - <name>j_pelvis_l</name> + <name>j_hip_yaw_l</name> <motion_module>walking</motion_module> </servo> <servo> - <name>j_thigh1_r</name> + <name>j_hip_roll_r</name> <motion_module>walking</motion_module> </servo> <servo> - <name>j_thigh1_l</name> + <name>j_hip_roll_l</name> <motion_module>walking</motion_module> </servo> <servo> - <name>j_thigh2_r</name> + <name>j_hip_pitch_r</name> <motion_module>walking</motion_module> </servo> <servo> - <name>j_thigh2_l</name> + <name>j_hip_pitch_l</name> <motion_module>walking</motion_module> </servo> <servo> - <name>j_tibia_r</name> + <name>j_knee_r</name> <motion_module>walking</motion_module> </servo> <servo> - <name>j_tibia_l</name> + <name>j_knee_l</name> <motion_module>walking</motion_module> </servo> <servo> - <name>j_ankle1_r</name> + <name>j_ankle_pitch_r</name> <motion_module>walking</motion_module> </servo> <servo> - <name>j_ankle1_l</name> + <name>j_ankle_pitch_l</name> <motion_module>walking</motion_module> </servo> <servo> - <name>j_ankle2_r</name> + <name>j_ankle_roll_r</name> <motion_module>walking</motion_module> </servo> <servo> - <name>j_ankle2_l</name> + <name>j_ankle_roll_l</name> <motion_module>walking</motion_module> </servo> <servo> diff --git a/src/xml/darwin_head.xml b/src/xml/darwin_head.xml deleted file mode 100644 index 1a848a78cf59e66be015eda5d3d9dbab94e975b4..0000000000000000000000000000000000000000 --- a/src/xml/darwin_head.xml +++ /dev/null @@ -1,86 +0,0 @@ -<?xml version="1.0"?> - -<darwin_config xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" - xsi:noNamespaceSchemaLocation="darwin_config.xsd"> - <servo> - <name>j_shoulder_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_shoulder_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_high_arm_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_high_arm_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_low_arm_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_low_arm_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_pelvis_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_pelvis_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_thigh1_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_thigh1_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_thigh2_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_thigh2_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_tibia_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_tibia_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_ankle1_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_ankle1_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_ankle2_r</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_ankle2_l</name> - <motion_module>action</motion_module> - </servo> - <servo> - <name>j_pan</name> - <motion_module>head</motion_module> - </servo> - <servo> - <name>j_tilt</name> - <motion_module>head</motion_module> - </servo> -</darwin_config> - diff --git a/src/xml/darwin_joints.xml b/src/xml/darwin_joints.xml deleted file mode 100644 index f79375fad8481137724efcf6270b61705f11800b..0000000000000000000000000000000000000000 --- a/src/xml/darwin_joints.xml +++ /dev/null @@ -1,86 +0,0 @@ -<?xml version="1.0"?> - -<darwin_config xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" - xsi:noNamespaceSchemaLocation="darwin_config.xsd"> - <servo> - <name>j_shoulder_r</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_shoulder_l</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_high_arm_r</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_high_arm_l</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_low_arm_r</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_low_arm_l</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_pelvis_r</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_pelvis_l</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_thigh1_r</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_thigh1_l</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_thigh2_r</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_thigh2_l</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_tibia_r</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_tibia_l</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_ankle1_r</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_ankle1_l</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_ankle2_r</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_ankle2_l</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_pan</name> - <motion_module>joints</motion_module> - </servo> - <servo> - <name>j_tilt</name> - <motion_module>joints</motion_module> - </servo> -</darwin_config> - diff --git a/src/xml/darwin_arm_kin.xsd b/src/xml/darwin_kin_chain.xsd similarity index 95% rename from src/xml/darwin_arm_kin.xsd rename to src/xml/darwin_kin_chain.xsd index 049e1a06bdf43902f69d6028193e4e967a86ed91..1cb71d91c167b37efee67065344867611f7e33e9 100644 --- a/src/xml/darwin_arm_kin.xsd +++ b/src/xml/darwin_kin_chain.xsd @@ -40,7 +40,7 @@ copyright : not copyrighted - public domain </xsd:sequence> </xsd:complexType> - <xsd:element name="darwin_arm_chain" type="joints_t"> + <xsd:element name="darwin_kin_chain" type="joints_t"> </xsd:element> </xsd:schema> diff --git a/src/xml/darwin_walk.xml b/src/xml/darwin_walk.xml deleted file mode 100644 index 7e46b8cb9d6f756307a933f23e1459c30da4e708..0000000000000000000000000000000000000000 --- a/src/xml/darwin_walk.xml +++ /dev/null @@ -1,86 +0,0 @@ -<?xml version="1.0"?> - -<darwin_config xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" - xsi:noNamespaceSchemaLocation="darwin_config.xsd"> - <servo> - <name>j_shoulder_r</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_shoulder_l</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_high_arm_r</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_high_arm_l</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_low_arm_r</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_low_arm_l</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_pelvis_r</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_pelvis_l</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_thigh1_r</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_thigh1_l</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_thigh2_r</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_thigh2_l</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_tibia_r</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_tibia_l</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_ankle1_r</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_ankle1_l</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_ankle2_r</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_ankle2_l</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_pan</name> - <motion_module>walking</motion_module> - </servo> - <servo> - <name>j_tilt</name> - <motion_module>walking</motion_module> - </servo> -</darwin_config> - diff --git a/src/xml/left_arm.xml b/src/xml/left_arm.xml index 62cd3a0e19c53f381ecb3cdc37aa0c1a678221b2..f4e2cd1d671bf29f4a5464636acce0c28296e182 100644 --- a/src/xml/left_arm.xml +++ b/src/xml/left_arm.xml @@ -1,7 +1,7 @@ <?xml version="1.0"?> -<darwin_arm_chain xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" - xsi:noNamespaceSchemaLocation="darwin_arm_chain.xsd"> +<darwin_kin_chain xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" + xsi:noNamespaceSchemaLocation="darwin_kin_chain.xsd"> <joint> <params> <a>-0.016</a> @@ -42,4 +42,4 @@ <max_angle>1.5707</max_angle> <min_angle>-1.5707</min_angle> </joint> -</darwin_arm_chain> +</darwin_kin_chain> diff --git a/src/xml/left_leg.xml b/src/xml/left_leg.xml new file mode 100644 index 0000000000000000000000000000000000000000..23eecbd17b4135a6964334c4e2aa291c3671c528 --- /dev/null +++ b/src/xml/left_leg.xml @@ -0,0 +1,65 @@ +<?xml version="1.0"?> + +<darwin_kin_chain xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" + xsi:noNamespaceSchemaLocation="darwin_kin_chain.xsd"> + <joint> + <params> + <a>0.0</a> + <alpha>1.5707</alpha> + <d>0.028652</d> + <theta>-1.5707</theta> + </params> + <max_angle>1.5707</max_angle> + <min_angle>-1.5707</min_angle> + </joint> + <joint> + <params> + <a>0.0</a> + <alpha>-1.5707</alpha> + <d>0.0</d> + <theta>1.5707</theta> + </params> + <max_angle>1.5707</max_angle> + <min_angle>-1.5707</min_angle> + </joint> + <joint> + <params> + <a>0.093</a> + <alpha>0.0</alpha> + <d>0.0</d> + <theta>0.0</theta> + </params> + <max_angle>1.5707</max_angle> + <min_angle>-1.5707</min_angle> + </joint> + <joint> + <params> + <a>0.093</a> + <alpha>3.14159</alpha> + <d>0.0</d> + <theta>0.0</theta> + </params> + <max_angle>1.5707</max_angle> + <min_angle>-1.5707</min_angle> + </joint> + <joint> + <params> + <a>0.0</a> + <alpha>1.5707</alpha> + <d>0.0</d> + <theta>0.0</theta> + </params> + <max_angle>1.5707</max_angle> + <min_angle>-1.5707</min_angle> + </joint> + <joint> + <params> + <a>0.0335</a> + <alpha>0.0</alpha> + <d>0.0</d> + <theta>0.0</theta> + </params> + <max_angle>1.5707</max_angle> + <min_angle>-1.5707</min_angle> + </joint> +</darwin_kin_chain> diff --git a/src/xml/right_arm.xml b/src/xml/right_arm.xml index c94f805280bc487eba827a4f4ac7472443446150..1b4e6a1411d42668d7a858f1b9670853fb92bc4e 100644 --- a/src/xml/right_arm.xml +++ b/src/xml/right_arm.xml @@ -1,7 +1,7 @@ <?xml version="1.0"?> -<darwin_arm_chain xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" - xsi:noNamespaceSchemaLocation="darwin_arm_chain.xsd"> +<darwin_kin_chain xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" + xsi:noNamespaceSchemaLocation="darwin_kin_chain.xsd"> <joint> <params> <a>-0.016</a> @@ -42,4 +42,4 @@ <max_angle>1.5707</max_angle> <min_angle>-1.5707</min_angle> </joint> -</darwin_arm_chain> +</darwin_kin_chain> diff --git a/src/xml/right_leg.xml b/src/xml/right_leg.xml new file mode 100644 index 0000000000000000000000000000000000000000..f5cef18b5d3115dfa0c251cfc8f10ed2b121ab0c --- /dev/null +++ b/src/xml/right_leg.xml @@ -0,0 +1,65 @@ +<?xml version="1.0"?> + +<darwin_kin_chain xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" + xsi:noNamespaceSchemaLocation="darwin_kin_chain.xsd"> + <joint> + <params> + <a>0.0</a> + <alpha>1.5707</alpha> + <d>0.028652</d> + <theta>-1.5707</theta> + </params> + <max_angle>1.5707</max_angle> + <min_angle>-1.5707</min_angle> + </joint> + <joint> + <params> + <a>0.0</a> + <alpha>1.5707</alpha> + <d>0.0</d> + <theta>1.5707</theta> + </params> + <max_angle>1.5707</max_angle> + <min_angle>-1.5707</min_angle> + </joint> + <joint> + <params> + <a>0.093</a> + <alpha>0.0</alpha> + <d>0.0</d> + <theta>0.0</theta> + </params> + <max_angle>1.5707</max_angle> + <min_angle>-1.5707</min_angle> + </joint> + <joint> + <params> + <a>0.093</a> + <alpha>3.14159</alpha> + <d>0.0</d> + <theta>0.0</theta> + </params> + <max_angle>1.5707</max_angle> + <min_angle>-1.5707</min_angle> + </joint> + <joint> + <params> + <a>0.0</a> + <alpha>-1.5707</alpha> + <d>0.0</d> + <theta>0.0</theta> + </params> + <max_angle>1.5707</max_angle> + <min_angle>-1.5707</min_angle> + </joint> + <joint> + <params> + <a>0.0335</a> + <alpha>0.0</alpha> + <d>0.0</d> + <theta>0.0</theta> + </params> + <max_angle>1.5707</max_angle> + <min_angle>-1.5707</min_angle> + </joint> +</darwin_kin_chain>