Skip to content
Snippets Groups Projects
Commit 63eb7ea1 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Added a driver for the new version of the darwin robot firmware.

parents
No related branches found
No related tags found
No related merge requests found
Showing with 1111 additions and 0 deletions
#include "darwin_robot.h"
#include "darwin_robot_exceptions.h"
#include <iostream>
std::string robot_device="A603LOBS";
int main(int argc, char *argv[])
{
int num_v1_servos,num_v2_servos;
std::vector<int> servos;
std::vector<double> angles,speeds,accels;
try{
CDarwin_Robot darwin("Darwin",robot_device,1000000,0xC0);
darwin.mm_get_num_servos(&num_v1_servos,&num_v2_servos);
std::cout << "Found " << num_v1_servos << " v1 servos and " << num_v2_servos << " v2 servos" << std::endl;
darwin.mm_enable_power();
sleep(1);
darwin.head_tracking_set_pan_pid(0.04,0.0,0.0);
darwin.head_tracking_set_tilt_pid(0.04,0.0,0.0);
darwin.mm_enable_servo(20);
darwin.mm_assign_module(20,DARWIN_MM_HEAD);
darwin.mm_start();
darwin.head_tracking_set_target(0.0,90.0);
darwin.head_tracking_start();
sleep(10);
darwin.head_tracking_set_target(0.0,0.0);
sleep(10);
darwin.mm_stop();
darwin.mm_disable_power();
}catch(CException &e){
std::cout << e.what() << std::endl;
}
}
#include "darwin_robot.h"
#include "darwin_robot_exceptions.h"
#include <iostream>
std::string robot_device="A603LOBS";
int main(int argc, char *argv[])
{
int i=0,num_v1_servos,num_v2_servos;
std::vector<double> angles;
short int accel_x,accel_y,accel_z;
short int gyro_x,gyro_y,gyro_z;
try{
CDarwin_Robot darwin("Darwin",robot_device,1000000,0xC0);
darwin.mm_get_num_servos(&num_v1_servos,&num_v2_servos);
std::cout << "Found " << num_v1_servos << " v1 servos and " << num_v2_servos << " v2 servos" << std::endl;
darwin.mm_enable_power();
// calibrate the imu
darwin.imu_start_gyro_cal();
while(!darwin.imu_is_gyro_cal_done())
{
std::cout << "waiting for the gyro to finish calibration" << std::endl;
usleep(100000);
}
darwin.imu_start();
for(i=1;i<=num_v1_servos+num_v2_servos;i++)
{
darwin.mm_enable_servo(i);
darwin.mm_assign_module(i,DARWIN_MM_JOINTS);
}
darwin.mm_start();
for(i=0;i<100000;i++)
{
darwin.imu_get_accel_data(&accel_x,&accel_y,&accel_z);
std::cout << accel_x << "," << accel_y << "," << accel_z << "," << i << std::endl;
darwin.imu_get_gyro_data(&gyro_x,&gyro_y,&gyro_z);
std::cout << gyro_x << "," << gyro_y << "," << gyro_z << std::endl;
darwin.adc_get_data();
angles=darwin.mm_get_servo_angles();
for(i=0;i<angles.size();i++)
std::cout << "Servo " << i << " angle: " << angles[i] << std::endl;
std::cout << "Period: " << darwin.mm_get_current_period() << " ms" << std::endl;
usleep(100000);
}
darwin.mm_stop();
std::cout << "ending" << std::endl;
darwin.imu_stop();
darwin.mm_disable_power();
}catch(CException &e){
std::cout << e.what() << std::endl;
}
}
#include "darwin_robot.h"
#include "darwin_robot_exceptions.h"
#include <iostream>
std::string robot_device="A603LOBS";
int main(int argc, char *argv[])
{
int num_v1_servos,num_v2_servos,i;
std::vector<int> servos;
std::vector<double> angles,speeds,accels;
try{
CDarwin_Robot darwin("Darwin",robot_device,1000000,0xC0);
darwin.mm_get_num_servos(&num_v1_servos,&num_v2_servos);
std::cout << "Found " << num_v1_servos << " v1 servos and " << num_v2_servos << " v2 servos" << std::endl;
darwin.mm_enable_power();
for(i=0;i<=27;i++)
{
darwin.mm_enable_servo(i);
darwin.mm_assign_module(i,DARWIN_MM_JOINTS);
}
darwin.mm_start();
servos.push_back(22);
servos.push_back(19);
angles.push_back(45.0);
angles.push_back(45.0);
speeds.push_back(10.0);
speeds.push_back(10.0);
accels.push_back(10.0);
accels.push_back(10.0);
std::cout << "Start joint_motion ..." << std::endl;
darwin.joints_load(servos,angles,speeds,accels);
darwin.joints_start();
while(darwin.are_joints_moving())
{
darwin.adc_get_data();
angles=darwin.mm_get_servo_angles();
for(i=0;i<angles.size();i++)
std::cout << "servo " << i << ": " << angles[i] << std::endl;
std::cout << "moving joints ..." << std::endl;
usleep(100000);
}
std::cout << "done" << std::endl;
return 0;
servos.push_back(20);
angles.clear();
angles.push_back(0.0);
angles.push_back(0.0);
speeds.push_back(10.0);
accels.push_back(10.0);
darwin.joints_load(servos,angles,speeds,accels);
darwin.joints_start();
while(darwin.are_joints_moving())
{
angles=darwin.mm_get_servo_angles();
std::cout << angles[19] << "," << angles[20] << std::endl;
std::cout << "moving joints ..." << std::endl;
usleep(100000);
}
darwin.mm_stop();
darwin.mm_disable_power();
}catch(CException &e){
std::cout << e.what() << std::endl;
}
}
#include "darwin_arm_kinematics.h"
#include "darwin_robot_exceptions.h"
#include <iostream>
std::string kin_file="../src/xml/right_arm.xml";
int main(int argc, char *argv[])
{
std::vector<double> joints_in(4),joints_out(4),pos,rot_out,rot_in(3,0.0);
int num_total=0,num_sol=0;
double i,j,k,l;
try{
CDarwinArmKinematics 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]);
kin.get_forward_kinematics(joints_in,pos,rot_out);
std::cout << pos[0] << "," << pos[1] << "," << pos[2] << std::endl;
return 0;
pos.push_back(0.0743671);
pos.push_back(0.0502218);
pos.push_back(0.0791303);
rot_in[0]=0;
rot_in[1]=0;
rot_in[2]=0;
kin.get_inverse_kinematics(pos,rot_in,joints_out);
std::cout << joints_out[0] << "," << joints_out[1] << "," << joints_out[2] << "," << joints_out[3] << std::endl;
return 0;
for(i=-1.5707;i<1.5707;i+=0.2)
{
for(j=-1.5707;j<1.5707;j+=0.2)
{
for(k=-1.5707;k<1.5707;k+=0.2)
{
for(l=-1.5707;l<1.5707;l+=0.2)
{
num_total++;
joints_in[0]=i;
joints_in[1]=j;
joints_in[2]=k;
joints_in[3]=l;
try{
std::cout << i << "," << j << "," << k << "," << l << std::endl;
kin.get_forward_kinematics(joints_in,pos,rot_out);
kin.get_inverse_kinematics(pos,rot_in,joints_out);
std::cout << joints_out[0] << "," << joints_out[1] << "," << joints_out[2] << "," << joints_out[3] << std::endl;
num_sol++;
}catch(CException &e){
std::cout << e.what() << std::endl;
}
}
}
}
}
std::cout << "Found " << num_sol << " solutions of " << num_total << " attempts" << std::endl;
}catch(CException &e){
std::cout << e.what() << std::endl;
}
}
#include "darwin_robot.h"
#include "darwin_robot_exceptions.h"
#include <iostream>
std::string robot_device="A603LOBS";
std::string config_file="../src/xml/darwin_action.xml";
int main(int argc, char *argv[])
{
int i=0,j=0,num_v1_servos,num_v2_servos;
std::vector<int> servos;
std::vector<double> angles,speeds,accels;
try{
CDarwin_Robot darwin("Darwin",robot_device,1000000,0xC0);
darwin.mm_load_config(config_file);
darwin.mm_get_num_servos(&num_v1_servos,&num_v2_servos);
std::cout << "Found " << num_v1_servos << " v1 servos and " << num_v2_servos << " v2 servos" << std::endl;
// execute the walk ready action
std::cout << "Assign servos to the action module" << std::endl;
darwin.mm_enable_power();
for(i=1;i<=num_v1_servos;i++)
{
darwin.mm_enable_servo(i);
darwin.mm_assign_module(i,DARWIN_MM_ACTION);
}
darwin.mm_start();
// execute an action
darwin.action_load_page(9);
darwin.action_start();
while(darwin.action_is_page_running())
{
std::cout << "Executing action ..." << std::endl;
std::cout << "Period: " << darwin.mm_get_current_period() << " ms" << std::endl;
usleep(100000);
}
// sit down
darwin.action_load_page(15);
darwin.action_start();
while(darwin.action_is_page_running())
{
std::cout << "Executing action ..." << std::endl;
std::cout << "Period: " << darwin.mm_get_current_period() << " ms" << std::endl;
usleep(100000);
}
// sit up
darwin.action_load_page(16);
darwin.action_start();
while(darwin.action_is_page_running())
{
std::cout << "Executing action ..." << std::endl;
std::cout << "Period: " << darwin.mm_get_current_period() << " ms" << std::endl;
usleep(100000);
}
/* walk forward for a while */
darwin.mm_stop();
for(i=1;i<=num_v1_servos;i++)
{
darwin.mm_enable_servo(i);
darwin.mm_assign_module(i,DARWIN_MM_WALKING);
}
darwin.mm_start();
darwin.walking_set_speeds(20,0,0);
darwin.walking_start();
sleep(2);
std::cout << "Stop walking ..." << std::endl;
darwin.walking_stop();
while(darwin.is_walking())
{
std::cout << "Walking ..." << std::endl;
std::cout << "Period: " << darwin.mm_get_current_period() << " ms" << std::endl;
usleep(100000);
}
/* move joints */
darwin.mm_stop();
for(i=1;i<=num_v1_servos;i++)
{
darwin.mm_enable_servo(i);
darwin.mm_assign_module(i,DARWIN_MM_JOINTS);
}
darwin.mm_start();
servos.push_back(1);
servos.push_back(3);
servos.push_back(5);
angles.push_back(45.0);
angles.push_back(45.0);
angles.push_back(45.0);
speeds.push_back(10.0);
speeds.push_back(10.0);
speeds.push_back(10.0);
accels.push_back(10.0);
accels.push_back(10.0);
accels.push_back(10.0);
std::cout << "Start joint_motion ..." << std::endl;
darwin.joints_load(servos,angles,speeds,accels);
darwin.joints_start();
while(darwin.are_joints_moving())
{
std::cout << "moving joints ..." << std::endl;
std::cout << "Period: " << darwin.mm_get_current_period() << " ms" << std::endl;
usleep(100000);
}
std::cout << "done" << std::endl;
/* head tracking */
darwin.mm_stop();
for(i=19;i<=20;i++)
{
darwin.mm_enable_servo(i);
darwin.mm_assign_module(i,DARWIN_MM_HEAD);
}
darwin.mm_start();
darwin.head_tracking_set_pan_pid(0.04,0.0,0.0);
darwin.head_tracking_set_tilt_pid(0.04,0.0,0.0);
darwin.head_tracking_set_target(0.0,90.0);
darwin.head_tracking_start();
for(i=0;i<40;i++)
{
std::cout << "head tracking ..." << std::endl;
std::cout << "Period: " << darwin.mm_get_current_period() << " ms" << std::endl;
usleep(10000);
}
darwin.head_tracking_stop();
darwin.mm_stop();
for(i=1;i<=num_v1_servos;i++)
{
darwin.mm_enable_servo(i);
darwin.mm_assign_module(i,DARWIN_MM_ACTION);
}
darwin.mm_start();
darwin.action_load_page(15);
darwin.action_start();
while(darwin.action_is_page_running())
{
std::cout << "Executing action ..." << std::endl;
std::cout << "Period: " << darwin.mm_get_current_period() << " ms" << std::endl;
usleep(100000);
}
/* disable servos and read position */
darwin.mm_stop();
for(i=1;i<=num_v1_servos;i++)
{
darwin.mm_disable_servo(i);
darwin.mm_assign_module(i,DARWIN_MM_NONE);
}
darwin.mm_start();
for(j=0;j<1000;j++)
{
angles=darwin.mm_get_servo_angles();
std::cout << "Period: " << darwin.mm_get_current_period() << " ms" << std::endl;
for(i=0;i<angles.size();i++)
std::cout << "Servo " << i << " angle: " << angles[i] << std::endl;
usleep(100000);
}
// enable all servos and assign them to the action module
darwin.mm_stop();
darwin.mm_disable_power();
}catch(CException &e){
std::cout << e.what() << std::endl;
}
}
#include "darwin_robot.h"
#include "darwin_robot_exceptions.h"
#include <iostream>
std::string robot_device="A603LOBS";
int main(int argc, char *argv[])
{
int i=0,num_v1_servos,num_v2_servos;
std::vector<double> angles;
try{
CDarwin_Robot darwin("Darwin",robot_device,1000000,0xC0);
darwin.mm_get_num_servos(&num_v1_servos,&num_v2_servos);
std::cout << "Found " << num_v1_servos << " v1 servos and " << num_v2_servos << " v2 servos" << std::endl;
// enable all servos and assign them to the action module
darwin.mm_enable_power();
for(i=1;i<=num_v1_servos;i++)
{
darwin.mm_enable_servo(i);
darwin.mm_assign_module(i,DARWIN_MM_ACTION);
}
darwin.mm_start();
// execute an action
darwin.action_load_page(9);
darwin.action_start();
while(darwin.action_is_page_running())
usleep(100000);
for(i=1;i<=num_v1_servos;i++)
darwin.mm_assign_module(i,DARWIN_MM_WALKING);
std::cout << "Start walking ..." << std::endl;
darwin.walking_set_speeds(20,0,0);
darwin.walking_start();
sleep(2);
std::cout << "Stop walking ..." << std::endl;
darwin.walking_stop();
while(darwin.is_walking())
{
std::cout << "Walking ..." << std::endl;
usleep(100000);
}
darwin.mm_stop();
darwin.mm_disable_power();
}catch(CException &e){
std::cout << e.what() << std::endl;
}
}
#check the existance of the xsd library
IF(EXISTS "/usr/include/xsd/cxx")
SET(HAVE_XSD TRUE PARENT_SCOPE)
SET(XSD_FOUND TRUE)
MESSAGE(STATUS "Found the XML library ... adding support for XML files")
FIND_LIBRARY(XSD_LIBRARY
NAMES xerces-c
PATHS /usr/lib /usr/local/lib)
ELSE(EXISTS "/usr/include/xsd/cxx")
MESSAGE(STATUS "XML library not found ... it will be impossible to handle XML files")
ENDIF(EXISTS "/usr/include/xsd/cxx")
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)
IF(XSD_FILES)
FOREACH(xsd_file ${XSD_FILES})
STRING(REGEX REPLACE "xsd" "cxx" xsd_source ${xsd_file})
SET(XSD_SOURCES_INT ${XSD_SOURCES_INT} ${XSD_PATH}/${xsd_source})
SET(XSD_SOURCES ${XSD_SOURCES} ${XSD_PATH}/${xsd_source})
STRING(REGEX REPLACE "xsd" "hxx" xsd_header ${xsd_file})
SET(XSD_HEADERS_INT ${XSD_HEADERS_INT} ${XSD_PATH}/${xsd_header})
SET(XSD_HEADERS ${XSD_HEADERS} ${XSD_PATH}/${xsd_header})
SET(XSD_PATH_FILES ${XSD_PATH_FILES} ${XSD_PATH}/${xsd_file})
ENDFOREACH(xsd_file)
SET(XSD_SOURCES ${XSD_SOURCES_INT} PARENT_SCOPE)
SET(XSD_HEADERS ${XSD_HEADERS_INT} PARENT_SCOPE)
ADD_CUSTOM_TARGET(xsd_files_gen DEPENDS ${XSD_SOURCES_INT})
ADD_CUSTOM_COMMAND(
OUTPUT ${XSD_SOURCES_INT}
COMMAND xsdcxx cxx-tree --generate-serialization ${XSD_FILES}
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}
DEPENDS ${XSD_PATH_FILES}
COMMENT "Parsing the xml template file ${XSD_FILES}")
INSTALL(FILES ${XSD_PATH_FILES} DESTINATION include/iridrivers/xml)
INSTALL(FILES ${XSD_HEADERS_INT} DESTINATION include/iridrivers/xml)
ENDIF(XSD_FILES)
ENDIF(XSD_FOUND)
<?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>
<?xml version="1.0"?>
<!--
file : darwin_config.xsd
author : Sergi Hernandez Juan (shernand@iri.upc.edu)
copyright : not copyrighted - public domain
-->
<xsd:schema xmlns:xsd="http://www.w3.org/2001/XMLSchema">
<xsd:complexType name="dh_t">
<xsd:sequence>
<xsd:element name="a" type="xsd:float">
</xsd:element>
<xsd:element name="alpha" type="xsd:float">
</xsd:element>
<xsd:element name="d" type="xsd:float">
</xsd:element>
<xsd:element name="theta" type="xsd:float">
</xsd:element>
</xsd:sequence>
</xsd:complexType>
<xsd:complexType name="joint_t">
<xsd:sequence>
<xsd:element name="params" type="dh_t">
</xsd:element>
<xsd:element name="max_angle" type="xsd:float">
</xsd:element>
<xsd:element name="min_angle" type="xsd:float">
</xsd:element>
</xsd:sequence>
</xsd:complexType>
<xsd:complexType name="joints_t">
<xsd:sequence>
<xsd:element name="joint" type="joint_t" maxOccurs="unbounded">
</xsd:element>
</xsd:sequence>
</xsd:complexType>
<xsd:element name="darwin_arm_chain" type="joints_t">
</xsd:element>
</xsd:schema>
<?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>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>head</motion_module>
</servo>
<servo>
<name>j_tilt</name>
<motion_module>head</motion_module>
</servo>
</darwin_config>
<?xml version="1.0"?>
<!--
file : darwin_config.xsd
author : Sergi Hernandez Juan (shernand@iri.upc.edu)
copyright : not copyrighted - public domain
-->
<xsd:schema xmlns:xsd="http://www.w3.org/2001/XMLSchema">
<xsd:simpleType name="motion_module_t">
<xsd:restriction base="xsd:string">
<xsd:enumeration value="action"/>
<xsd:enumeration value="walking"/>
<xsd:enumeration value="joints"/>
<xsd:enumeration value="head"/>
<xsd:enumeration value="gripper"/>
</xsd:restriction>
</xsd:simpleType>
<xsd:simpleType name="servo_name_t">
<xsd:restriction base="xsd:string">
<xsd:enumeration value="j_shoulder_r"/>
<xsd:enumeration value="j_shoulder_l"/>
<xsd:enumeration value="j_high_arm_r"/>
<xsd:enumeration value="j_high_arm_l"/>
<xsd:enumeration value="j_low_arm_r"/>
<xsd:enumeration value="j_low_arm_l"/>
<xsd:enumeration value="j_pelvis_r"/>
<xsd:enumeration value="j_pelvis_l"/>
<xsd:enumeration value="j_thigh1_r"/>
<xsd:enumeration value="j_thigh1_l"/>
<xsd:enumeration value="j_thigh2_r"/>
<xsd:enumeration value="j_thigh2_l"/>
<xsd:enumeration value="j_tibia_r"/>
<xsd:enumeration value="j_tibia_l"/>
<xsd:enumeration value="j_ankle1_r"/>
<xsd:enumeration value="j_ankle1_l"/>
<xsd:enumeration value="j_ankle2_r"/>
<xsd:enumeration value="j_ankle2_l"/>
<xsd:enumeration value="j_pan"/>
<xsd:enumeration value="j_tilt"/>
</xsd:restriction>
</xsd:simpleType>
<xsd:complexType name="servo_config_t">
<xsd:sequence>
<xsd:element name="name" type="servo_name_t">
</xsd:element>
<xsd:element name="motion_module" type="motion_module_t">
</xsd:element>
</xsd:sequence>
</xsd:complexType>
<xsd:complexType name="darwin_config_t">
<xsd:sequence>
<xsd:element name="servo" type="servo_config_t" maxOccurs="unbounded">
</xsd:element>
</xsd:sequence>
</xsd:complexType>
<xsd:element name="darwin_config" type="darwin_config_t">
</xsd:element>
</xsd:schema>
<?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>
<?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>
<?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>
<?xml version="1.0"?>
<darwin_arm_chain xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:noNamespaceSchemaLocation="darwin_arm_chain.xsd">
<joint>
<params>
<a>-0.016</a>
<alpha>1.5707</alpha>
<d>0.02165</d>
<theta>3.14159</theta>
</params>
<max_angle>1.5707</max_angle>
<min_angle>-1.5707</min_angle>
</joint>
<joint>
<params>
<a>-0.06</a>
<alpha>1.5707</alpha>
<d>-0.016</d>
<theta>-0.7854</theta>
</params>
<max_angle>1.5707</max_angle>
<min_angle>-1.5707</min_angle>
</joint>
<joint>
<params>
<a>-0.02165</a>
<alpha>1.5707</alpha>
<d>0</d>
<theta>0</theta>
</params>
<max_angle>1.5707</max_angle>
<min_angle>-1.5707</min_angle>
</joint>
<joint>
<params>
<a>0</a>
<alpha>0</alpha>
<d>0.056</d>
<theta>0</theta>
</params>
<max_angle>1.5707</max_angle>
<min_angle>-1.5707</min_angle>
</joint>
</darwin_arm_chain>
<?xml version="1.0"?>
<darwin_arm_chain xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:noNamespaceSchemaLocation="darwin_arm_chain.xsd">
<joint>
<params>
<a>-0.016</a>
<alpha>-1.5707</alpha>
<d>0.02165</d>
<theta>3.14159</theta>
</params>
<max_angle>1.5707</max_angle>
<min_angle>-1.5707</min_angle>
</joint>
<joint>
<params>
<a>-0.06</a>
<alpha>1.5707</alpha>
<d>-0.016</d>
<theta>0.7854</theta>
</params>
<max_angle>1.5707</max_angle>
<min_angle>-1.5707</min_angle>
</joint>
<joint>
<params>
<a>-0.02165</a>
<alpha>1.5707</alpha>
<d>0</d>
<theta>0</theta>
</params>
<max_angle>1.5707</max_angle>
<min_angle>-1.5707</min_angle>
</joint>
<joint>
<params>
<a>0</a>
<alpha>0</alpha>
<d>0.056</d>
<theta>0</theta>
</params>
<max_angle>1.5707</max_angle>
<min_angle>-1.5707</min_angle>
</joint>
</darwin_arm_chain>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment