toolkittest.cpp
Go to the documentation of this file.
1 
2 #include"kdl/kdltk/toolkit.hpp"
3 #include<kdl/kinfam/joint_io.hpp>
4 #include<kdl/kinfam/joint.hpp>
5 #include<rtt/os/main.h>
6 #include<rtt/Logger.hpp>
7 #include<rtt/TaskContext.hpp>
8 #include<kdl/kinfam/kuka361.hpp>
9 #include<kdl/kinfam/unittransmission.hpp>
10 #include<kdl/kinfam/lineartransmission.hpp>
11 
12 using namespace RTT;
13 using namespace KDL;
14 
15 int ORO_main(int argc, char** argv)
16 {
17  RTT::Toolkit::Import(KDLToolkit);
18 
19  TaskContext writer("writer");
20  int retval = 0;
21 
22  JointTransX tx(Frame(Rotation::RPY(1,2,3),Vector(1,2,3)));
23  JointTransY ty(Frame(Rotation::RPY(1,2,3),Vector(1,2,3)));
24  JointTransZ tz(Frame(Rotation::RPY(1,2,3),Vector(1,2,3)));
25  JointRotX rx(Frame(Rotation::RPY(1,2,3),Vector(1,2,3)));
26  JointRotY ry(Frame(Rotation::RPY(1,2,3),Vector(1,2,3)));
27  JointRotZ rz(Frame(Rotation::RPY(1,2,3),Vector(1,2,3)));
28 
29  Property<JointTransX> tx_prop("joint1","first joint",tx);
30  Property<JointTransY> ty_prop("joint2","second joint",ty);
31  Property<JointTransZ> tz_prop("joint3","third joint",tz);
32  Property<JointRotX> rx_prop("joint4","fourth joint",rx);
33  Property<JointRotY> ry_prop("joint5","fifth joint",ry);
34  Property<JointRotZ> rz_prop("joint6","sixth joint",rz);
35  Kuka361 kuka = Kuka361();
36  SerialChain* robot = kuka.createSerialChain();
37  LinearTransmission ltrans = LinearTransmission(6,vector<double>(6,1),vector<double>(6,0.5));
38  Property<LinearTransmission> ltrans_prop("transmission","some transmission",ltrans);
39  UnitTransmission utrans = UnitTransmission(6);
40  Property<UnitTransmission> utrans_prop("transmission2","some other transmission",utrans);
41 
42  Property<SerialChain> kuka_prop("testchain","some chain",*(robot));
43  Property<ZXXZXZ> kuka_prop2("testchain2","some other chain",kuka);
44 
45  writer.properties()->addProperty(&tx_prop);
46  writer.properties()->addProperty(&ty_prop);
47  writer.properties()->addProperty(&tz_prop);
48  writer.properties()->addProperty(&rx_prop);
49  writer.properties()->addProperty(&ry_prop);
50  writer.properties()->addProperty(&rz_prop);
51  writer.properties()->addProperty(&ltrans_prop);
52  writer.properties()->addProperty(&utrans_prop);
53  writer.properties()->addProperty(&kuka_prop);
54  writer.properties()->addProperty(&kuka_prop2);
55 
56  writer.marshalling()->writeProperties("test.cpf");
57 
58  writer.marshalling()->readProperties("test.cpf");
59  Logger::In in("KDLToolkitTest");
60  if(tx_prop.value().getType()!=tx.getType()||!Equal(tx_prop.value().frame_before_joint(),tx.frame_before_joint(),1e-5)){
61  log(Error)<<"Property is not the same after writing and rereading"<<endlog();
62  log(Debug)<<"Property "<<tx_prop.value()<<" ,actual type: "<<tx<<endlog();
63  retval=-1;
64  }
65 
66  if(ty_prop.value().getType()!=ty.getType()||!Equal(ty_prop.value().frame_before_joint(),ty.frame_before_joint(),1e-5)){
67  log(Error)<<"Property is not the same after writing and rereading"<<endlog();
68  log(Debug)<<"Property "<<ty_prop.value()<<" ,actual type: "<<ty<<endlog();
69  retval=-1;
70  }
71 
72  if(tz_prop.value().getType()!=tz.getType()||!Equal(tz_prop.value().frame_before_joint(),tz.frame_before_joint(),1e-5)){
73  log(Error)<<"Property is not the same after writing and rereading"<<endlog();
74  log(Debug)<<"Property "<<tz_prop.value()<<" ,actual type: "<<tz<<endlog();
75  retval=-1;
76  }
77 
78  if(rx_prop.value().getType()!=rx.getType()||!Equal(rx_prop.value().frame_before_joint(),rx.frame_before_joint(),1e-5)){
79  log(Error)<<"Property is not the same after writing and rereading"<<endlog();
80  log(Debug)<<"Property "<<rx_prop.value()<<" ,actual type: "<<rx<<endlog();
81  retval=-1;
82  }
83 
84  if(ry_prop.value().getType()!=ry.getType()||!Equal(ry_prop.value().frame_before_joint(),ry.frame_before_joint(),1e-5)){
85  log(Error)<<"Property is not the same after writing and rereading"<<endlog();
86  log(Debug)<<"Property "<<ry_prop.value()<<" ,actual type: "<<ry<<endlog();
87  retval=-1;
88  }
89 
90  if(rz_prop.value().getType()!=rz.getType()||!Equal(rz_prop.value().frame_before_joint(),rz.frame_before_joint(),1e-5)){
91  log(Error)<<"Property is not the same after writing and rereading"<<endlog();
92  log(Debug)<<"Property "<<rz_prop.value()<<" ,actual type: "<<rz<<endlog();
93  retval=-1;
94  }
95 
96 
97  delete robot;
98  return retval;
99 
100 }
INLINE Rall1d< T, V, S > log(const Rall1d< T, V, S > &arg)
Definition: rall1d.h:305
int ORO_main(int argc, char **argv)
Definition: toolkittest.cpp:15
IMETHOD bool Equal(const FrameAcc &r1, const FrameAcc &r2, double eps=epsilon)
Definition: frameacc.hpp:394
A concrete implementation of a 3 dimensional vector class.
Definition: frames.hpp:162
represents a frame transformation in 3D space (rotation + translation)
Definition: frames.hpp:572


orocos_kdl
Author(s):
autogenerated on Thu Apr 13 2023 02:19:14