|
From: <sac...@us...> - 2008-06-11 23:28:40
|
Revision: 763
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=763&view=rev
Author: sachinchitta
Date: 2008-06-11 16:28:49 -0700 (Wed, 11 Jun 2008)
Log Message:
-----------
Removed libKDL from build for now. Will be tested and added later since it does not seem to exist for Feisty.
Modified Paths:
--------------
pkg/trunk/drivers/robot/pr2/libpr2API/Makefile
pkg/trunk/drivers/robot/pr2/libpr2API/include/libpr2API/pr2API.h
pkg/trunk/drivers/robot/pr2/libpr2API/manifest.xml
pkg/trunk/drivers/robot/pr2/libpr2API/src/pr2API.cpp
Added Paths:
-----------
pkg/trunk/util/kinematics/libKDL/include/libKDL/
pkg/trunk/util/kinematics/libKDL/include/libKDL/kdl_kinematics.h
Removed Paths:
-------------
pkg/trunk/util/kinematics/libKDL/include/kdl_kinematics.h
Modified: pkg/trunk/drivers/robot/pr2/libpr2API/Makefile
===================================================================
--- pkg/trunk/drivers/robot/pr2/libpr2API/Makefile 2008-06-11 23:15:45 UTC (rev 762)
+++ pkg/trunk/drivers/robot/pr2/libpr2API/Makefile 2008-06-11 23:28:49 UTC (rev 763)
@@ -18,7 +18,7 @@
LIBP = lib/libpr2API.a
LIBS = lib/libpr2API.so
-all: $(LIBP) test_libpr2API bin/pr2_kin_kdl
+all: $(LIBP) test_libpr2API
pr2API.o: src/pr2API.cpp include/libpr2API/pr2API.h
$(CXX) $(CFLAGS) -c -o $@ $<
@@ -33,9 +33,6 @@
test_libpr2API: src/test/test_pr2API.cpp $(LIBP)
$(CXX) $(CFLAGS) -o $@ $< $(LFLAGS)
-bin/pr2_kin_kdl: src/test/pr2_kin_kdl.cpp $(LIBP)
- $(CXX) $(CFLAGS) -o $@ $< $(LFLAGS)
-
clean:
-rm -f test_libpr2API $(LIBP) $(LIBS) bin/*
-rm -rf *.o $(PKG) $(PKG).dSYM
Modified: pkg/trunk/drivers/robot/pr2/libpr2API/include/libpr2API/pr2API.h
===================================================================
--- pkg/trunk/drivers/robot/pr2/libpr2API/include/libpr2API/pr2API.h 2008-06-11 23:15:45 UTC (rev 762)
+++ pkg/trunk/drivers/robot/pr2/libpr2API/include/libpr2API/pr2API.h 2008-06-11 23:28:49 UTC (rev 763)
@@ -39,7 +39,9 @@
#include <stdint.h>
#include <string>
+#ifdef KDL_KINEMATICS
#include <kdl_kinematics.h> // for kinematics using KDL -- util/kinematics/libKDL
+#endif
namespace PR2
{
@@ -449,8 +451,11 @@
//public: PR2_ERROR_CODE SetArmCartesianPosition(PR2_MODEL_ID id, double effectorPosition[], double effectorSpeed[]);
public: PR2_ERROR_CODE SetArmCartesianPosition(PR2_MODEL_ID id, NEWMAT::Matrix g);
- // KDL version of SetArmCartesianPosition
+
+#ifdef KDL_KINEMATICS
+// KDL version of SetArmCartesianPosition
public: PR2_ERROR_CODE SetArmCartesianPosition(PR2_MODEL_ID id, KDL::Frame f);
+#endif
/*! \fn
\brief Get the commanded position and speed for the end-effector
@@ -629,8 +634,10 @@
protected: PR2_CONTROL_MODE armControlMode[2];
protected: PR2_CONTROL_MODE baseControlMode;
protected: PR2Arm myArm;
- public: PR2_kinematics pr2_kin; // for kinematics using KDL.
+#ifdef KDL_KINEMATICS
+ public: PR2_kinematics pr2_kin; // for kinematics using KDL.
+#endif
/*! \fn
\brief - Oscillate the Hokuyo, return point cloud
*/
Modified: pkg/trunk/drivers/robot/pr2/libpr2API/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/libpr2API/manifest.xml 2008-06-11 23:15:45 UTC (rev 762)
+++ pkg/trunk/drivers/robot/pr2/libpr2API/manifest.xml 2008-06-11 23:28:49 UTC (rev 763)
@@ -11,7 +11,6 @@
<depend package="gazebo"/>
<depend package="pr2Core"/>
<depend package="libKinematics"/>
-<depend package="libKDL"/>
<export>
<cpp cflags="-I${prefix}/include" lflags="-L${prefix}/lib -lpr2API"/>
</export>
Modified: pkg/trunk/drivers/robot/pr2/libpr2API/src/pr2API.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/libpr2API/src/pr2API.cpp 2008-06-11 23:15:45 UTC (rev 762)
+++ pkg/trunk/drivers/robot/pr2/libpr2API/src/pr2API.cpp 2008-06-11 23:28:49 UTC (rev 763)
@@ -591,6 +591,8 @@
return PR2_ALL_OK;
};
+#ifdef KDL_KINEMATICS
+
PR2_ERROR_CODE PR2Robot::SetArmCartesianPosition(PR2_MODEL_ID id, KDL::Frame f)
{
KDL::JntArray q_init = KDL::JntArray(this->pr2_kin.nJnts);
@@ -612,8 +614,8 @@
for(int ii = 0; ii < 7; ii++)
this->SetJointServoCmd((PR2::PR2_JOINT_ID) (JointStart[id]+ii),q_out(ii),0);
}
+#endif
-
PR2_ERROR_CODE PR2Robot::SetArmCartesianPosition(PR2_MODEL_ID id, NEWMAT::Matrix g)
{
NEWMAT::Matrix theta(8,8);
Deleted: pkg/trunk/util/kinematics/libKDL/include/kdl_kinematics.h
===================================================================
--- pkg/trunk/util/kinematics/libKDL/include/kdl_kinematics.h 2008-06-11 23:15:45 UTC (rev 762)
+++ pkg/trunk/util/kinematics/libKDL/include/kdl_kinematics.h 2008-06-11 23:28:49 UTC (rev 763)
@@ -1,47 +0,0 @@
-
-#ifndef KDL_KINEMATICS_H
-#define KDL_KINEMATICS_H
-
-#include <kdl/chain.hpp>
-#include <kdl/chainfksolver.hpp>
-#include <kdl/chainfksolverpos_recursive.hpp>
-#include <kdl/chainfksolvervel_recursive.hpp>
-#include <kdl/chainiksolvervel_pinv.hpp>
-#include <kdl/chainiksolverpos_nr.hpp>
-#include <kdl/kinfam_io.hpp>
-#include <kdl/frames_io.hpp>
-#include <kdl/framevel_io.hpp>
-#include <stdio.h>
-#include <iostream>
-#include <math.h>
-
-#include <pr2Core/pr2Core.h>
-
-#define RTOD(r) ((r)*180/M_PI)
-#define DTOR(d) ((d)*M_PI/180)
-
-double modulus_double(double a, double b);
-double angle_within_mod180(double ang);
-void angle_within_mod180(KDL::JntArray &q, int nJnts);
-
-class PR2_kinematics
-{
- private:
- KDL::Chain *chain;
- KDL::ChainFkSolverPos_recursive *fk_pos_solver;
- KDL::ChainIkSolverVel_pinv *ik_vel_solver;
- KDL::ChainIkSolverPos_NR *ik_pos_solver;
-
- public:
- int nJnts;
-
- public:
- PR2_kinematics();
- bool FK(const KDL::JntArray &q, KDL::Frame &f);
- bool IK(const KDL::JntArray &q_init, const KDL::Frame &f, KDL::JntArray &q_out);
-
-};
-
-#endif
-
-
Copied: pkg/trunk/util/kinematics/libKDL/include/libKDL/kdl_kinematics.h (from rev 761, pkg/trunk/util/kinematics/libKDL/include/kdl_kinematics.h)
===================================================================
--- pkg/trunk/util/kinematics/libKDL/include/libKDL/kdl_kinematics.h (rev 0)
+++ pkg/trunk/util/kinematics/libKDL/include/libKDL/kdl_kinematics.h 2008-06-11 23:28:49 UTC (rev 763)
@@ -0,0 +1,47 @@
+
+#ifndef KDL_KINEMATICS_H
+#define KDL_KINEMATICS_H
+
+#include <kdl/chain.hpp>
+#include <kdl/chainfksolver.hpp>
+#include <kdl/chainfksolverpos_recursive.hpp>
+#include <kdl/chainfksolvervel_recursive.hpp>
+#include <kdl/chainiksolvervel_pinv.hpp>
+#include <kdl/chainiksolverpos_nr.hpp>
+#include <kdl/kinfam_io.hpp>
+#include <kdl/frames_io.hpp>
+#include <kdl/framevel_io.hpp>
+#include <stdio.h>
+#include <iostream>
+#include <math.h>
+
+#include <pr2Core/pr2Core.h>
+
+#define RTOD(r) ((r)*180/M_PI)
+#define DTOR(d) ((d)*M_PI/180)
+
+double modulus_double(double a, double b);
+double angle_within_mod180(double ang);
+void angle_within_mod180(KDL::JntArray &q, int nJnts);
+
+class PR2_kinematics
+{
+ private:
+ KDL::Chain *chain;
+ KDL::ChainFkSolverPos_recursive *fk_pos_solver;
+ KDL::ChainIkSolverVel_pinv *ik_vel_solver;
+ KDL::ChainIkSolverPos_NR *ik_pos_solver;
+
+ public:
+ int nJnts;
+
+ public:
+ PR2_kinematics();
+ bool FK(const KDL::JntArray &q, KDL::Frame &f);
+ bool IK(const KDL::JntArray &q_init, const KDL::Frame &f, KDL::JntArray &q_out);
+
+};
+
+#endif
+
+
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|