Browse Source

finish doxygen

master
philipp schoenberger 10 years ago
parent
commit
fe62f8db91
  1. 1
      lwrserv/include/BangBangTrajectory.h
  2. 0
      lwrserv/include/FivePolyTrajectory.h
  3. 11
      lwrserv/include/Mat.h
  4. 4
      lwrserv/include/Robot.h
  5. 22
      lwrserv/include/SvrData.h
  6. 77
      lwrserv/include/Trajectroy.h
  7. 10
      lwrserv/include/lwr4.h
  8. 210
      lwrserv/src/SocketObject.cpp
  9. 353
      lwrserv/src/SvrData.cpp
  10. 18
      lwrserv/src/SvrHandling.cpp
  11. 148
      lwrserv/src/commands.cpp
  12. 77
      lwrserv/src/program.cpp
  13. 61
      lwrserv/trajectory/start.m
  14. 12501
      lwrserv/trajectory/trajectory_1.csv

1
lwrserv/include/BangBangTrajectory.h

@ -104,7 +104,6 @@ class BangBangJointTrajectory : public Trajectory<SIZE>
// <=>
// a = s* 2 / t^2
Vec<float,SIZE> currMaxAcceleration = (jointMovementAbs * 2.0f ).celldivide(this->steps).celldivide(this->steps)*2.0f;
std::cout << "currMaxAcceleration : " << currMaxAcceleration << "\n";
float count = 0.0f;
for( int i = 0 ; i < this->steps; ++i)

0
lwrserv/include/FivePolyTrajectory.h

11
lwrserv/include/Mat.h

@ -249,17 +249,6 @@ public:
// " = " + (L-Val = R-Val)
}
#if 0
Mat<T, SIZE> operator * (const Vec<T, SIZE> &vec)
{
Vec<T, SIZE> buf;
for (unsigned int j=0; j<SIZE; j++) // column j
for (unsigned int i=0; i<SIZE; i++) // row i
buf(i) += m_aatData[i][j]*vec(j);
return buf;
}
#endif
Mat<T,SIZE> abs()
{
Mat<T,SIZE> buf;

4
lwrserv/include/Robot.h

@ -15,9 +15,8 @@ class Robot
public:
/// number of joints for the default robot
static const unsigned int joints = LBR_MNJ;
unsigned int joints;
/// typdef for a vector witch can hold a value for each joint
///@TODO find a better solution for a general joint vector escpecial if the joint numbers could be varify for different robots:
typedef Vec<float,joints> VecJoint;
protected:
@ -34,7 +33,6 @@ class Robot
*/
Robot()
{
this->joints = LBR_MNJ;
this->jointRangeMin = VecJoint(-180.0f);
this->jointRangeMax = VecJoint(+180.0f);
this->jointVelocity = VecJoint(+100.0f);

22
lwrserv/include/SvrData.h

@ -18,17 +18,27 @@
class SvrData: public Singleton
{
private:
/// measured units from the robot
struct {
/// current measured joint position in [ degree ]
Robot::VecJoint jointPos;
/// current measured homogeneous cartesian position
MatCarthesian cartPos;
/// current measured force and torque for the end effector in [ Nm ]
VecTorque forceAndTorque;
/// current measured Jacobian matrix for the robot
float jacobian[FRI_CART_VEC * Robot::joints];
} messured;
} measured;
// commanded position for the robot
struct {
// the last commanded position for the joint angles
Robot::VecJoint jointPos;
// the last commanded position for the homogeneous cartesian position
MatCarthesian cartPos;
} commanded;
struct {
Robot* robotClass;
float currentVelocityPercentage;
@ -69,14 +79,12 @@ public:
void updateMeasurement();
int getMeasuredJacobian(float* data, size_t size);
VecTorque getMeasuredForceTorque();
Robot::VecJoint getMeasuredJointPos();
MatCarthesian getMeasuredCartPos();
int getMessuredJacobian(float* data, size_t size);
VecTorque getMessuredForceTorque();
Robot::VecJoint getMessuredJointPos();
MatCarthesian getMessuredCartPos();
Robot::VecJoint getCommandedJointPos();
void setCommandedJointPos(Robot::VecJoint newJointPos);
@ -87,6 +95,7 @@ public:
Robot::VecJoint getMaxVelocity();
Robot::VecJoint getMaxAcceleration();
Robot::VecJoint getMaxRange();
Robot::VecJoint getMinRange();
bool checkJointRange(Robot::VecJoint vectorToCheck);
@ -99,6 +108,7 @@ public:
int setRobotAccelerationPercentage(float newAccelerationPercentage);
unsigned int getJoints();
class Robot* getRobot();
// trajectory functions
float getSampleTimeMs();

77
lwrserv/include/Trajectroy.h

@ -22,15 +22,14 @@ template <unsigned SIZE> class Trajectory;
#include "LinearTrajectory.h"
#include "LSPBTrajectory.h"
#include "BangBangTrajectory.h"
#include "FivePolyTrajectory.h"
/**
* enumeration of all suppored Trajectorys.
* @info How to add a new Trajectory
* enumeration of all suppored trajectorys.
* @info How to add a new trajectory
* First of all add a Include line in this file.
* You should add the new Trajectories in this Enumeration
* Also in the initTrajectoryType initalisation Routine and GetTrajectory should be extended
* for the new Trajectory Type.
* for the new trajectory Type.
*
* @warning __TrajectoryCount should alsways be the last item in the list
*
@ -45,9 +44,6 @@ enum TrajectoryType {
TrajectoryJointBangBang,
TrajectoryCartBangBang,
TrajectoryJointFivePoly,
TrajectoryCartFivePoly,
TrajectoryJointLSPB,
TrajectoryCartLSPB,
__TrajectoryCount
@ -65,7 +61,7 @@ static struct TrajectoryTypeStr{
}* trajectoryTypeStr = NULL;
/**
* This function initalize the help structure for the String/Enum convert functions
* This function initialize the help structure for the string/enumeration convert functions
*
* @see toEnum
* @see toString
@ -87,9 +83,6 @@ static void initTrajectoryType ()
trajectoryTypeStr[i].type = TrajectoryJointBangBang;
trajectoryTypeStr[i].str = "JointBangBang";
++i;
trajectoryTypeStr[i].type = TrajectoryJointFivePoly;
trajectoryTypeStr[i].str = "JointFivePoly";
++i;
trajectoryTypeStr[i].type = TrajectoryCartLinear;
trajectoryTypeStr[i].str = "CartLinear";
@ -100,17 +93,14 @@ static void initTrajectoryType ()
trajectoryTypeStr[i].type = TrajectoryCartBangBang;
trajectoryTypeStr[i].str = "CartBangBang";
++i;
trajectoryTypeStr[i].type = TrajectoryCartFivePoly;
trajectoryTypeStr[i].str = "CartFivePoly";
++i;
}
}
/**
* This function converts the enumeration type of a Trajectory to a std::string
* This function converts the enumeration type of a trajectory to a std::string
*
* @parameter type Type of the Trajectory
* @retval string of the Trajectory of "default" if no trajectory was matched
* @param type Type of the trajectory
* @retval string of the trajectory of "default" if no trajectory was matched
*
* @see toEnum
* @see initTrajectoryType
@ -119,19 +109,23 @@ static std::string toString(enum TrajectoryType type)
{
initTrajectoryType();
int items = __TrajectoryCount;
// search within the array for a type match
for (int i = 0 ; i < items ; ++i)
{
if (trajectoryTypeStr[i].type == type)
return ""+ trajectoryTypeStr[i].str;
}
// nothing found return the default string
return "default";
}
/**
* This function converts the string of a Trajectory back to a enumeration id
* This function converts the string of a trajectory back to a enumeration id
*
* @parameter name String containing the Trajectory type
* @retval Trajectory id or default if no Trajectory was found
* @param name String containing the trajectory type
* @retval trajectory id or default if no trajectory was found
*
* @see toString
* @see initTrajectoryType
@ -177,14 +171,14 @@ class Trajectory
nodes = NULL;
}
/**
* Normal constructor for a Joint based Trajectory
* Trajectory is computed within the constructor and contains a stepwise
* Normal constructor for a joint based trajectory
* trajectory is computed within the constructor and contains a stepwise
* movement from jointStart to the jointEnd.
*
* The Trajectoy class just uses a one step Trajectory
* for smarter Trajectories use BangBang, LSPB or Linear
* The trajectory class just uses a one step trajectory
* for smarter trajectories use BangBang, LSPB or Linear
*
* @param sampleTimeMs The timestep for each step within the Trajectory
* @param sampleTimeMs The timestep for each step within the trajectory
* @param maxJointVelocity The maximum velocity for each Joint of the Robot
* @param maxJointAcceleration The maximum acceleration for each Joint of the Robot
* @param jointStart The joint angles of the starting point
@ -217,21 +211,21 @@ class Trajectory
(void)maxJointAcceleration;
}
/**
* Normal constructor for a Joint based Trajectory
* Trajectory is computed within the constructor and contains a stepwise
* Normal constructor for a Joint based trajectory
* trajectory is computed within the constructor and contains a stepwise
* movement from jointStart to the jointEnd.
*
* The Trajectory class just uses a one step Trajectory
* The trajectory class just uses a one step trajectory
* for smarter Trajectories use BangBang, LSPB or Linear
*
* @param type The enumeration id of the Trajectory to convert to
* @param sampleTimeMs The time step for each step within the Trajectory
* @param type The enumeration id of the trajectory to convert to
* @param sampleTimeMs The time step for each step within the trajectory
* @param maxJointVelocity The maximum velocity for each Joint of the Robot
* @param maxJointAcceleration The maximum acceleration for each Joint of the Robot
* @param jointStart The joint angles of the starting point
* @param jointEnd The end position for each joint after running the trajectory
*
* @return A valid pointer to a new Instance for a Trajectory between the start and end point.
* @return A valid pointer to a new Instance for a trajectory between the start and end point.
*
* @info memory deletion has to be done by the receiver for the class
*/
@ -259,14 +253,11 @@ class Trajectory
case TrajectoryJointLSPB:
retval = (class Trajectory<SIZE>*) new LSPBJointTrajectory<SIZE>(sampleTimeMs, maxJointVelocity, maxJointAcceleration, jointStart, jointEnd);
break;
case TrajectoryJointFivePoly:
break;
//@TODO implement Cartesian movement
case TrajectoryCartLSPB:
case TrajectoryCartLinear:
case TrajectoryCartBangBang:
case TrajectoryCartFivePoly:
retval = (class Trajectory<SIZE>*) new LinearJointTrajectory<SIZE>(sampleTimeMs, maxJointVelocity, maxJointAcceleration, jointStart, jointEnd);
break;
}
@ -274,7 +265,7 @@ class Trajectory
}
/**
* Destructor for each Trajectory which frees the step container
* Destructor for each trajectory which frees the step container
* Inherent Classes does not need any destructor if no extra fields are allocated within these.
*/
virtual ~Trajectory()
@ -327,12 +318,12 @@ class Trajectory
/**
* Returns a Vector with new angles for the Robot
* If end of the Trajectory is reached it always returns the
* If end of the trajectory is reached it always returns the
* last joint angles.
* If there is not even one step in the Trajectory it returns a Vector
* If there is not even one step in the trajectory it returns a Vector
* containing zeros.
*
* @info only returns valid values if this is a joint based Trajectory
* @info only returns valid values if this is a joint based trajectory
*
* @retval Vector containing the next joint angles
*
@ -445,7 +436,7 @@ class Trajectory
* If there is not even one step in the trajectory it returns the
* zero vector
*
* @info only returns valid values if this is a Cartesian based trajectory
* @info only returns valid values if this is a cartesian based trajectory
*
* @param step id of the needed position
* @retval joint vector containing the position
@ -466,7 +457,7 @@ class Trajectory
step = steps-1;
}
// only if there is a step container allocated and the trajectory is of type Cartesian
// only if there is a step container allocated and the trajectory is of type cartesian
if (nodes != NULL && movementType == MovementCartBased)
{
retval = nodes[step].cartPos;
@ -558,9 +549,9 @@ class Trajectory
{
/// joint angles only used for joint based trajectories
Vec<float,SIZE> jointPos;
/// Cartesian position only used for Cartesian based trajectories
/// Cartesian position only used for cartesian based trajectories
MatCarthesian cartPos;
/// velocity for all Joint
/// velocity for all joint
Vec<float,SIZE> velocity;
/// acceleration for all joints
Vec<float,SIZE> acceleration;
@ -600,7 +591,7 @@ class Trajectory
/// array of the trajectory containing parameters for each step
struct trajectoryNode* nodes;
/// movement type of the trajectory which is Cartesian or Joint based
/// movement type of the trajectory which is Cartesian or joint based
enum MovementType movementType;
};

10
lwrserv/include/lwr4.h

@ -1,8 +1,5 @@
#ifndef _LWR4_H_
#define _LWR4_H_
#include "Vec.h"
#include "Mat.h"
#include "friComm.h"
#include "Robot.h"
/**
@ -47,17 +44,18 @@ class LWR4 : public Robot
// the LWR4 robot has 7 Joints
// use the macro from fri remote
public :
unsigned int joints;
LWR4();
LWR4::VecJoint backwardCalc(MatCarthesian pos, struct RobotConfig config );
Robot::VecJoint backwardCalc(MatCarthesian pos, struct RobotConfig config );
MatCarthesian forwardCalc(Robot::VecJoint, struct RobotConfig config );
};
/**
* default constructor for the lwr4 robot which is seting up all constraints
*/
LWR4::LWR4()
{
joints = LBR_MNJ;
float jointRangeMax_[] = { 170.0f, 120.0f, 170.0f, 120.0f, 170.0f, 120.0f, 170.0f};
float jointRangeMin_[] = {-170.0f,-120.0f,-170.0f,-120.0f,-170.0f,-120.0f,-170.0f};
float jointVelocity_[] = { 110.0f, 110.0f, 128.0f, 128.0f, 204.0f, 184.0f, 184.0f};

210
lwrserv/src/SocketObject.cpp

@ -8,6 +8,9 @@
#include <iomanip>
#if defined(__msdos__) || defined(WIN32)
/**
* default constructor for the client server interface object
*/
SocketObject::SocketObject(void)
{
#ifdef __SOCKET_OBJECT_DEBUG
@ -21,6 +24,10 @@ SocketObject::SocketObject(void)
WSAStartup(wVersionRequested, &wsaData);
}
/**
* copy constructor for the server object.
* @param sk the source server object
*/
SocketObject::SocketObject(SocketObject& sk)
{
WSADATA wsaData;
@ -32,6 +39,10 @@ SocketObject::SocketObject(SocketObject& sk)
WSAStartup(wVersionRequested, &wsaData);
}
/**
* copy constructor for the server object.
* @param sk the source server object
*/
SocketObject::~SocketObject(void)
{
Disconnect();
@ -39,6 +50,11 @@ SocketObject::~SocketObject(void)
#endif
/**
* This function sets the blocking mode for the
* server object.
* @param nonblock the new blocking mode
*/
void SocketObject::setBlockingMode(bool nonblock)
{
int errorCode = 0;
@ -53,121 +69,148 @@ void SocketObject::setBlockingMode(bool nonblock)
errorCode = WSAGetLastError();
cout << "Set blocking mode ("<<iMode<<") failed! Errorcode "<< errorCode;
}
#else
#else // not __msdos__
//CHANGED: Use the boolean value
if (nonblock)
fcntl(_skSocket, F_SETFL, O_NONBLOCK);
#endif
// TODO reset if changed again to block
#endif // end not __msdos__
}
/**
* This function sets up the server object
* to listen to the provided port.
* @param iPort the port to bind the server socket to
* @return 0 if the bind procedure was correct and a negative error code otherwise
*/
int SocketObject::Bind(unsigned short int iPort)
{
#if defined(__msdos__) || defined(WIN32)
struct sockaddr_in saServerAddress;
// TCP-Socket erschaffen
// create a tcp socket
_skSocket = socket(AF_INET, SOCK_STREAM, 0);
if (_skSocket == INVALID_SOCKET)
{
#ifdef __SOCKET_OBJECT_DEBUG
#ifdef __SOCKET_OBJECT_DEBUG
std::cout << "SocketObject::Bind(): INVALID SOCKET" << end::endl;
#endif
#endif
return 0;
}
// serverAdress wählen
// setup the server address
memset(&saServerAddress, 0, sizeof(sockaddr_in));
saServerAddress.sin_family = AF_INET;
saServerAddress.sin_addr.s_addr = htonl(INADDR_ANY);
saServerAddress.sin_port = htons(iPort);
// bind the server address to the socket
if ( bind(_skSocket, (sockaddr*)&saServerAddress, sizeof(sockaddr))== SOCKET_ERROR)
{
Disconnect();
return -1;
} else
{
#ifdef __SOCKET_OBJECT_DEBUG
#ifdef __SOCKET_OBJECT_DEBUG
std::cout << "SocketObject::Bind(): Alles ok" << std::endl;
#endif
#endif
return 0;
}
#else
#else // not __msdos__
struct sockaddr_in saServerAddress;
#ifdef __SOCKET_OBJECT_DEBUG
std::cout << "Port: " << iPort << std::endl;
#endif
// Socket erschaffen
_skSocket = socket(AF_INET, SOCK_STREAM, 0);
if (_skSocket < 0)
{
#ifdef __SOCKET_OBJECT_DEBUG
#ifdef __SOCKET_OBJECT_DEBUG
std::cout << "Error: on creating socket" << std::endl;
#endif
#endif
return -1;
}
const int y = 1;
/* Socketoptionen fuer schnelles Verbinden setzen*/
// set the socket option for a fast connection */
setsockopt(_skSocket, SOL_SOCKET, SO_REUSEADDR, &y, sizeof(int));
/* Initialisieren der aockaddr_in - structure */
// Server-Adresse mit 0 vorbelegen
// initialize the sockaddr_in structure
// set server address to zero
memset(&saServerAddress, 0, sizeof(struct sockaddr_in));
// Domain
// type of socket address
saServerAddress.sin_family = AF_INET;
// Addresse
// accept from any ip address
saServerAddress.sin_addr.s_addr = INADDR_ANY;
// Port
// use the defined port to listen to
saServerAddress.sin_port = htons( iPort );
// Versuch Socket an Port zu binden
if (0 > bind(_skSocket, (sockaddr*) &saServerAddress, sizeof(sockaddr)))
// bind the socket to the initialized server address
int err = bind(_skSocket, (sockaddr*) &saServerAddress, sizeof(sockaddr));
if (0 > err)
{
// Socket will nicht mehr lesen und schreiben
// socket address setup was incorrect
shutdown(_skSocket,2);
#ifdef __SOCKET_OBJECT_DEBUG
#ifdef __SOCKET_OBJECT_DEBUG
std::cout << "Error: on bind" << std::endl;
#endif
return -1;
#endif
return err;
} else
{
return 0;
}
#endif
#endif // not __msdos__
}
/**
* This function listens on the socket and might
* be waiting for a receiving message
*
* @return 0 if there are messages and a negative error code otherwise
* @see setBlockingMode
*/
int SocketObject::Listen( void )
{
// lauscht bei _skSocket, max Warteschlange = 2
// listens to the server socket. max queue = 2
return listen(_skSocket, 2);
// WIN32 : ,32
}
/**
* This function accepts a connection from the client socket
* and produces a new client connection socket.
*
* @param skAcceptSocket the destination object for the client socket which will be accepted
* @return true if the accept was successfully and false otherwise
*/
bool SocketObject::Accept(SocketObject &skAcceptSocket)
{
struct sockaddr_in saClientAddress;
int iClientSize = sizeof(sockaddr_in);
#if defined(__msdos__) || defined(WIN32)
// gab the new client connection socket
skAcceptSocket._skSocket = accept(_skSocket, (struct sockaddr*)&saClientAddress, &iClientSize);
// check if the client socket is a correct one
return !( skAcceptSocket._skSocket == INVALID_SOCKET);
#else
// gab the new client connection socket
skAcceptSocket._skSocket = accept( _skSocket, (sockaddr*) &saClientAddress,(socklen_t*) &iClientSize);
// check if the client socket is a correct one
return !( skAcceptSocket._skSocket == -1);
#endif
}
/**
* This function connects to a server address.
* @param szServerAddress the server address to connect to
* @param iPort the post of the server address
* @param nonblock if the connection will be a nonblocking one
*
* @return true if the connect was successfully and false otherwise
*/
bool SocketObject::Connect(const char* szServerAddress, unsigned short int iPort, bool nonblock)
{
#if defined(__msdos__) || defined(WIN32)
@ -181,17 +224,19 @@ bool SocketObject::Connect(const char* szServerAddress, unsigned short int iPort
if (_skSocket == INVALID_SOCKET)
return false;
// setup the block mode if needed
u_long iMode = 0;
if (nonblock)
iMode = 1;
ioctlsocket(_skSocket, FIONBIO, &iMode);
// initialize the server address structure
memset(&server_addr,0,sizeof(struct sockaddr_in));
server_addr.sin_family = AF_INET;
server_addr.sin_addr.s_addr = inet_addr(szServerAddress);
if (server_addr.sin_addr.s_addr == INADDR_NONE)
{
// convert the name to address
lpHost = gethostbyname(szServerAddress);
if (lpHost != NULL)
{
@ -200,8 +245,9 @@ bool SocketObject::Connect(const char* szServerAddress, unsigned short int iPort
else
return false;
}
server_addr.sin_port = htons(iPort);
// actually do the connect with the server address structure
error = connect(_skSocket, (struct sockaddr*)&server_addr, sizeof(sockaddr));
if (error == SOCKET_ERROR)
{
@ -210,7 +256,7 @@ bool SocketObject::Connect(const char* szServerAddress, unsigned short int iPort
}
return true;
#else
#else // non __msdos__
struct sockaddr_in server_addr;
int status;
@ -220,10 +266,11 @@ bool SocketObject::Connect(const char* szServerAddress, unsigned short int iPort
if (_skSocket < 0)
return false;
// setup block mode if needed
if (nonblock)
fcntl(_skSocket, F_SETFL, O_NONBLOCK);
// initialize der sockaddr_in- Struktur
// initialize der sockaddr_in structure
memset(&server_addr, 0, sizeof(struct sockaddr_in));
server_addr.sin_family = AF_INET;
server_addr.sin_addr.s_addr = inet_addr(szServerAddress);
@ -242,11 +289,23 @@ bool SocketObject::Connect(const char* szServerAddress, unsigned short int iPort
#endif
}
/**
* This function connects to a server address.
* @param szServerAddress the server address to connect to
* @param iPort the post of the server address
* @param nonblock if the connection will be a nonblocking one
*
* @return true if the connect was successfully and false otherwise
*/
bool SocketObject::Connect(const std::string szServerAddress, unsigned short int iPort, bool nonblock)
{
return Connect((char*) szServerAddress.c_str(), iPort, nonblock);
}
/**
* This function kills a connection and frees the socket.
*/
void SocketObject::Disconnect()
{
#if defined(__msdos__) || defined(WIN32)
@ -255,37 +314,55 @@ void SocketObject::Disconnect()
closesocket(_skSocket);
_skSocket = INVALID_SOCKET;
}
#else
#else // non __msdos__
close(_skSocket);
#endif
#endif// end non __msdos__
}
/**
* This function receives the next message within the socket.
*
* @param szBuffer the destination buffer for the message
* @param iBufferLength the length of the buffer to prevent segmentation faults
* @param iFlags the flag for the receive function
* @returns the number of bytes of the received message
*/
int SocketObject::Recv(char *szBuffer, int iBufferLength, int iFlags)
{
return recv(_skSocket, szBuffer, iBufferLength, iFlags);
}
/**
* This function receives the next message within the socket.
*
* @param s the string buffer for the receive function
* @returns the length of the received message
*/
int SocketObject::Recv (std::string& s)
{
// create a local buffer
char buf [MAXRECV+1];
// std::cout << WSAGetLastError() << " in SocketObject::Recv, vor recv" << std::endl;
s = "";
memset(buf, 0, MAXRECV+1);
// do the receive
int status = Recv(buf, MAXRECV, 0);
// check for the received size
switch (status)
{
case -1:
#ifdef __SOCKET_OBJECT_DEBUG
#ifdef __SOCKET_OBJECT_DEBUG
std::cout << "status: -1 errno: " << errno << " in SocketObject::Recv" << std::endl;
#endif
#endif
break;
case 0:
break;
default:
// copy the buffer to the string
s = buf;
// strip the (expected) CRLF
// strip the (expected) CRLF like \n \r
if(s.length() == 1)
{
if(s[s.length()-1]=='\n' || s[s.length()-1]=='\r')
@ -302,22 +379,34 @@ int SocketObject::Recv (std::string& s)
return status;
}
/**
* This function receives the message and stops on
* the linebreak symbol.
*
* @param array the destination array for all lines
* @param arraySize the size of the array
* @returns the length of the received message
*/
int SocketObject::receiveLine(char* array, int arraySize)
{
char r;
int pos = 0;
// keep receiving until we filled up the buffer
while (pos<arraySize-2)
{
// receive only one char
switch(recv(_skSocket, &r, 1, 0))
{
case 0: // not connected anymore;
case 0: // no message any more
return 0;
case -1:
case -1: // an error happed
return -1;
}
// check for carriage return or line feed (MAC: CR, Linux: LF, Windows: CRLF)
// char(13) = '\r'
// char(10) = '\n'
if ((r == char(13)) || (r == char(10)))
{
if (pos > 0)
@ -334,6 +423,12 @@ int SocketObject::receiveLine(char* array, int arraySize)
return pos;
}
/**
* This function receives the message and stops on
* the linebreak symbol.
*
* @returns the string object containing the message
*/
std::string SocketObject::receiveLine()
{
std::string ret;
@ -358,6 +453,8 @@ std::string SocketObject::receiveLine()
}
// check for carriage return or line feed (MAC: CR, Linux: LF, Windows: CRLF)
// char(13) = '\r'
// char(10) = '\n'
if ((r == char(13)) || (r == char(10)))
{
if (ret.length() > 0)
@ -369,11 +466,25 @@ std::string SocketObject::receiveLine()
}
}
/**
* This function sends a message provided by the parameter.
*
* @param szBuffer the char message which should be send
* @param iBufferLength the length of the message
* @param iFlags the flag for the sending function
* @returns the amount of bytes send via the socket
*/
int SocketObject::Send(const char *szBuffer, int iBufferLength, int iFlags)
{
return send(_skSocket,szBuffer,iBufferLength, iFlags);
}
/**
* This function sends a message provided by the parameter.
*
* @param s the string message which should be send
* @returns the amount of bytes send via the socket
*/
int SocketObject::Send (const std::string s)
{
std::string str = s;
@ -399,8 +510,9 @@ int SocketObject::Send (const std::string s)
}
#if defined(__msdos__) || defined(WIN32)
return Send((char*) str.c_str(), (int) str.size(), 0);
#else
#else // non __msdos__
return Send((char*) str.c_str(), (int) str.size(), (int) MSG_NOSIGNAL);
#endif
#endif // end non __msdos__
}

353
lwrserv/src/SvrData.cpp

@ -10,8 +10,8 @@
#include "Mat.h"
#include "Vec.h"
#include "Robot.h"
#include "lwr4.h"
#include "Robot.h"
bool SvrData::instanceFlag = false;
SvrData* SvrData::single = 0;
@ -34,7 +34,7 @@ SvrData::SvrData(void)
robot.currentAccelerationPercentage = 10;
// use the lwr4 robot by default
robot.robotClass = new LWR4();
robot.robotClass = (class Robot*)new LWR4();
// use 5ms interval for each step
trajectory.sampleTimeMs = 5.0f;
@ -117,9 +117,9 @@ void SvrData::updateMeasurementData(
{
pthread_mutex_lock(&dataLock);
this->messured.jointPos = newJointPos;
this->messured.cartPos = newCartPos;
this->messured.forceAndTorque = newForceAndTorque;
this->measured.jointPos = newJointPos;
this->measured.cartPos = newCartPos;
this->measured.forceAndTorque = newForceAndTorque;
pthread_mutex_unlock(&dataLock);
}
@ -155,47 +155,6 @@ void SvrData::updateMeasurement()
updateMeasurementData(newJointPos,newCartPos,newForceAndTorque);
}
/**
* This function returns the current measurement of the joints
* within the database.
* This value will be updated if updateMeasurement was called
* which is done by the robot server thread.
*
* @see updateMeasurement
* @see threadRobotMovement
*/
Robot::VecJoint SvrData::getMeasuredJointPos()
{
Robot::VecJoint buf;
pthread_mutex_lock(&dataLock);
buf = messured.jointPos;
pthread_mutex_unlock(&dataLock);
return buf;
}
/**
* This function returns the current measurement homogeneous
* cartesian positions within the database.
*
* This value will be updated if updateMeasurement was called
* which is done by the robot server thread.
*
* @see updateMeasurement
* @see threadRobotMovement
*/
MatCarthesian SvrData::getMessuredCartPos()
{
MatCarthesian buf;
pthread_mutex_lock(&dataLock);
buf = messured.cartPos;
pthread_mutex_unlock(&dataLock);
return buf;
}
/**
* This function returns the current measurement force and
* torque within the database.
@ -206,12 +165,12 @@ MatCarthesian SvrData::getMessuredCartPos()
* @see updateMeasurement
* @see threadRobotMovement
*/
VecTorque SvrData::getMessuredForceTorque()
VecTorque SvrData::getMeasuredForceTorque()
{
VecTorque buf;
pthread_mutex_lock(&dataLock);
buf = messured.forceAndTorque;
buf = measured.forceAndTorque;
pthread_mutex_unlock(&dataLock);
return buf;
@ -231,15 +190,15 @@ VecTorque SvrData::getMessuredForceTorque()
* @see updateMeasurement
* @see threadRobotMovement
*/
int SvrData::getMessuredJacobian(float* data, size_t size)
int SvrData::getMeasuredJacobian(float* data, size_t size)
{
if (data == NULL)
return -EINVAL;
if (size != sizeof(messured.jacobian))
if (size != sizeof(measured.jacobian))
return -EINVAL;
pthread_mutex_lock(&dataLock);
memcpy(data,messured.jacobian,size);
memcpy(data,measured.jacobian,size);
pthread_mutex_unlock(&dataLock);
return 0;
@ -395,58 +354,73 @@ Robot::VecJoint SvrData::getMinRange()
}
/**
* This function returns the current minimum range per joint
* for the configured Robot.
* This function checks with the current configured robot
* the valid range
*
* @return Vector containing the minimum angle for the joints [ degree ]
* @return Vector containing the angle for the joints [ degree ]
*/
bool SvrData::checkJointRange(Robot::VecJoint vectorToCheck)
{
// save temporal the max range for short time lock
bool retval = false;
pthread_mutex_lock(&dataLock);
Vec<float,LBR_MNJ> maxJointRange;
maxJointRange = robot.max.range;
retval = this->robot.robotClass->validateJointRange(vectorToCheck);
pthread_mutex_unlock(&dataLock);
// check if the value is in plus or minus range
for (int i = 0; i< robot.robotClass->joints; i++)
{
if (abs(vectorToCheck(i)) > abs(maxJointRange(i)))
{
// join angle is too big
return false;
}
}
// no join angle is too big
return true;
return retval;
}
/**
* This function sets the current percentage of the
* maximum velocity for the configured Robot.
* The percentage has to be in the interval of (0,100]
* to be valid.
*
* @param newVelocityPercentage the new percentage value
* @return 0 if it was successfully otherwise the negative Error Code
*/
int SvrData::setRobotVelocityPercentage(float newVelocityPercentage)
{
unsigned int retval = 0;
// percentage is to low
if (newVelocityPercentage <= 0.0f)
return -1;
return -EINVAL;
// percentage is to high
if (newVelocityPercentage > 100.0f)
return -2;
return -EINVAL;
pthread_mutex_lock(&dataLock);
robot.currentVelocityPercentage = newVelocityPercentage;
pthread_mutex_unlock(&dataLock);
return retval;
}
/**
* This function returns the current velocity of the configured Robot.
*
* @return The velocity in [ degree/seconds ]
*/
Robot::VecJoint SvrData::getRobotVelocity()
{
float percent = 0.0f;
Robot::VecJoint retval(0.0f);
pthread_mutex_lock(&dataLock);
// calculate the multiplier for the max velocity
percent = robot.currentVelocityPercentage / 100.0f;
retval = robot.robotClass->getJointVelocity() * percent;
pthread_mutex_unlock(&dataLock);
return retval;
}
/**
* This function returns the current percentage of the maximum velocity
* of the configured robot.
*
* @return The percentage within the interval of (0,100]
*/
float SvrData::getRobotVelocityPercentage()
{
float retval = 0;
@ -457,34 +431,56 @@ float SvrData::getRobotVelocityPercentage()
return retval;
}
/**
* This function sets the current percentage of the maximum acceleration
* of the configured robot.
*
* @param newAccelerationPercentage the new percentage value for the acceleration
* @return 0 if the new values was set correctly and the negative Error code otherwise
*/
int SvrData::setRobotAccelerationPercentage(float newAccelerationPercentage)
{
int retval = 0;
// percentage is to low
if (newAccelerationPercentage <= 0.0f)
return -1;
return -EINVAL;
// percentage is to high
if (newAccelerationPercentage > 100.0f)
return -2;
return -EINVAL;
pthread_mutex_lock(&dataLock);
robot.currentAccelerationPercentage = newAccelerationPercentage;
pthread_mutex_unlock(&dataLock);
return retval;
return 0;
}
/**
* This function returns the current acceleration
* of the configured robot.
*
* @return the current acceleration in [ degree / seconds^2 ]
*/
Robot::VecJoint SvrData::getRobotAcceleration()
{
float percent = 0;
Robot::VecJoint retval(0.0f);
pthread_mutex_lock(&dataLock);
// calculate the percentage multiplier
percent = robot.currentAccelerationPercentage / 100.0f;
retval = robot.robotClass->getJointAcceleration() * percent;
pthread_mutex_unlock(&dataLock);
return retval;
}
/**
* This function returns the current percentage of acceleration
* of the configured robot.
*
* @return the current acceleration in [ percent ]
*/
float SvrData::getRobotAccelerationPercentage()
{
float retval = 0;
@ -495,18 +491,47 @@ float SvrData::getRobotAccelerationPercentage()
return retval;
}
/**
* This function returns the robot class reference
* @info robot class has only get/calculate function so returning
* the reference could not do any harm
*
* @return the reference to the robot instance
*/
class Robot* SvrData::getRobot()
{
class Robot* retval;
pthread_mutex_lock(&dataLock);
retval = this->robot.robotClass;
pthread_mutex_unlock(&dataLock);
return retval;
}
/**
* This function returns the joint number of the current robot
* class
*
* @return the number of joints of the current robot
*/
unsigned int SvrData::getJoints()
{
unsigned int retval = 0;
pthread_mutex_lock(&dataLock);
retval = Robot::joints;
retval = this->robot.robotClass->joints;
pthread_mutex_unlock(&dataLock);
return retval;
}
/// Trajectory function
/**
* This function returns the current configured sample time of the robot
*
* @return the time interval of the FRI Interface in [ milliseconds ]
*/
float SvrData::getSampleTimeMs()
{
float retval = 0;
@ -514,26 +539,43 @@ float SvrData::getSampleTimeMs()
pthread_mutex_lock(&dataLock);
retval = trajectory.sampleTimeMs;
pthread_mutex_unlock(&dataLock);
return retval;
}
/**
* This function changes the sample time of the FRI interface.
* The unit is in [ milliseconds ].
* The time interval must be within the interval (0, infinity)
*
* @return 0 if the sample interval was set correctly and the negative error code otherwise
*/
int SvrData::setSampleTimeMs(float newSampleTimeMs)
{
int retval = 0;
// sample time can not be negative or 0
if (newSampleTimeMs <= 0.0f)
return -1;
return -EINVAL;
pthread_mutex_lock(&dataLock);
trajectory.sampleTimeMs = newSampleTimeMs;
pthread_mutex_unlock(&dataLock);
return retval;
return 0;
}
/**
* This function grabs the next trajectory from the list.
* The time interval must be within the interval (0, infinity)
*
* @return a valid Trajectory pointer if the next trajectory could be grabbed.
* Otherwise the returnvalue will be NULL, which also could be happen if there is no trajectory.
*/
class Trajectory<Robot::joints>* SvrData::popTrajectory()
{
class Trajectory<Robot::joints>* retval = NULL;
pthread_mutex_lock(&dataLock);
// check if there is a trajectory
if (!trajectory.list.empty() )
{
retval = trajectory.list.front();
@ -541,12 +583,21 @@ class Trajectory<Robot::joints>* SvrData::popTrajectory()
}
else
{
// no trajectroy left
// no trajectory left set the signal that each trajectory was grabbed
trajectory.done = true;
}
pthread_mutex_unlock(&dataLock);
return retval;
}
/**
* This function grabs the next trajectory from the list.
* The time interval must be within the interval (0, infinity)
*
* @return a valid Trajectory pointer if the next trajectory could be grabbed.
* Otherwise the returnvalue will be NULL, which also could be happen if there is no trajectory.
*/
int SvrData::pushTrajectory(class Trajectory<Robot::joints>* newTrajectory)
{
if (newTrajectory == NULL)
@ -558,15 +609,37 @@ int SvrData::pushTrajectory(class Trajectory<Robot::joints>* newTrajectory)
pthread_mutex_unlock(&dataLock);
return 0;
}
/**
* This function grabs the flag if the current trajectory has to be
* canceled.
*
* @return true if the trajectory has to be about
* Otherwise the returnvalue will be NULL, which also could be happen if there is no trajectory.
*
* @see cancelCurrentTrajectory
*/
bool SvrData::getTrajectoryCancel()
{
bool retval = false;
pthread_mutex_lock(&dataLock);
retval = trajectory.cancel;
pthread_mutex_unlock(&dataLock);
return retval;
}
/**
* This function sets the cancel flag and deletes all trajectories within the queue.
* The current trajectory will be canceled when the server thread sees the cancel flag.
*
* @return true if the trajectory has to be about
* Otherwise the returnvalue will be NULL, which also could be happen if there is no trajectory.
*
* @return true if all trajectory could be canceled and the flag could be set correctly. Otherwise false.
* @see getTrajectoryCancel
*/
bool SvrData::cancelCurrentTrajectory()
{
pthread_mutex_lock(&dataLock);
@ -596,8 +669,16 @@ bool SvrData::cancelCurrentTrajectory()
pthread_mutex_unlock(&dataLock);
boost::this_thread::sleep( boost::posix_time::milliseconds(trajectory.sampleTimeMs) );
}
return true;
}
/**
* This function resets the cancel flag.
*
* @see getTrajectoryCancel
* @see getTrajectoryDone
*/
void SvrData::trajectoryCancelDone()
{
pthread_mutex_lock(&dataLock);
@ -605,6 +686,14 @@ void SvrData::trajectoryCancelDone()
pthread_mutex_unlock(&dataLock);
}
/**
* This function returns if the server thread canceled the trajectory correcly.
*
* @return true if the trajectory was canceled false otherwise.
*
* @see getTrajectoryCancel
* @see trajectoryCancelDone
*/
bool SvrData::getTrajectoryDone()
{
bool retval = true;
@ -614,6 +703,14 @@ bool SvrData::getTrajectoryDone()
return retval;
}
/**
* This function returns the current configured type of trajectory.
*
* @return the enumeration id of the current trajectory type
*
* @see TrajectoryType
* @see setTrajectoryType
*/
enum TrajectoryType SvrData::getTrajectoryType()
{
enum TrajectoryType retval = TrajectoryDefault;
@ -622,6 +719,15 @@ enum TrajectoryType SvrData::getTrajectoryType()
pthread_mutex_unlock(&dataLock);
return retval;
}
/**
* This function changes the configured type of trajectory.
*
* @param newType the new enumeration id of the new type
*
* @see TrajectoryType
* @see getTrajectoryType
*/
void SvrData::setTrajectoryType(enum TrajectoryType newType)
{
pthread_mutex_lock(&dataLock);
@ -629,6 +735,16 @@ void SvrData::setTrajectoryType(enum TrajectoryType newType)
pthread_mutex_unlock(&dataLock);
}
/**
* This function creates an instance of the current configured
* trajectory from the last commanded position to the parameter
* provided.
*
* @param newJointPos the new commanded position defined by joints
*
* @see TrajectoryType
* @see createTrajectory
*/
class Trajectory<Robot::joints>* SvrData::createTrajectory(Robot::VecJoint newJointPos)
{
//set new target for next trajectory
@ -640,45 +756,106 @@ class Trajectory<Robot::joints>* SvrData::createTrajectory(Robot::VecJoint newJo
Robot::VecJoint maxJointAcceleration = getRobotAcceleration();
enum TrajectoryType type = getTrajectoryType();
//newTrajectory = SvrData::getInstance()->createTrajectory(newJointPos);
if ( this->getTrajectoryPotfieldMode() == false)
newTrajectory = Trajectory<Robot::joints>::GetTrajectory(type,sampleTimeMs, maxJointVelocity, maxJointAcceleration, prevJointPos, newJointPos);
else
newTrajectory = new Trajectory<Robot::joints>(sampleTimeMs, maxJointVelocity, maxJointAcceleration, prevJointPos, newJointPos);
return newTrajectory;
}
class Trajectory<Robot::joints>* SvrData::createTrajectory(MatCarthesian newJointPos)
/**
* This function creates an instance of the current configured
* trajectory from the last commanded position to the parameter
* provided.
*
* @param newCartPos the new commanded position defined by the homogeneous cartesian position
*
* @see TrajectoryType
* @see createTrajectory
*/
class Trajectory<Robot::joints>* SvrData::createTrajectory(MatCarthesian newCartPos)
{
(void) newJointPos;
// unimplemented
return NULL;
// TODO check all combinations and take the one with the minimal joint movement
struct Robot::RobotConfig robotconfig;
robotconfig.elbow = false;
robotconfig.flip = false;
robotconfig.j1os = false;
// calculate the joint angle for the position
Robot::VecJoint newJointPos = this->robot.robotClass->backwardCalc(newCartPos,robotconfig);
return createTrajectory(newJointPos);
}
/**
* This function returns the current measured position for each
* joint.
* These values will be updated by the server via the updateMeasurement
* function.
*
* @return the current joint positions in [ degree ]
*
* @see updateMeasurement
* @see updateMeasurementData
*/
Robot::VecJoint SvrData::getMeasuredJointPos()
{
Robot::VecJoint retval(0.0f);
pthread_mutex_lock(&dataLock);
retval = messured.jointPos;
retval = measured.jointPos;
pthread_mutex_unlock(&dataLock);
return retval;
}
/**
* This function returns the measured homogenious cartesian postition.
* These values will be updated by the server via the updateMeasurement
* function.
*
* @return the homogenious cartesian position
*
* @see updateMeasurement
* @see updateMeasurementData
*/
MatCarthesian SvrData::getMeasuredCartPos()
{
MatCarthesian retval(0.0f,1.0f);
pthread_mutex_lock(&dataLock);
retval = messured.cartPos;
retval = measured.cartPos;
pthread_mutex_unlock(&dataLock);
return retval;
}
/**
* This function sets the flag to start the potential field mode.
*
* @param newstate the new state of the flag. False to stop and true to start the potential field mode.
* @see getTrajectoryPotfieldMode
*/
void SvrData::setTrajectoryPotfieldMode(bool newstate)
{
pthread_mutex_lock(&dataLock);
trajectory.potfieldmode = newstate;
pthread_mutex_unlock(&dataLock);
}
/**
* This function returns the flag of the potential file mode.
*
* @return True if the potential field mode is active and false otherwise.
*
* @see setTrajectoryPotfieldMode
*/
bool SvrData::getTrajectoryPotfieldMode()
{
bool retval = false;
pthread_mutex_lock(&dataLock);
retval = trajectory.potfieldmode;
pthread_mutex_unlock(&dataLock);
return retval;
}

18
lwrserv/src/SvrHandling.cpp

@ -48,10 +48,9 @@ void printUsage(SocketObject& client, std::string& cmd)
}
/**
* Normal Constructor
* Initalizes the command array with long/short string version
* Normal constructor
* Initializes the command array with long/short string version
* for the commands.
* Also sets function pointers for processing
* and printing the detailed help information for each command
@ -136,6 +135,14 @@ SvrHandling::SvrHandling()
commandCount = i;
}
/**
* the thread for the robot movement.
* This Thread signals within each tic defined by the sample
* time the current commanded trajectory position.
*
* @param arg unused
* @return should not happen and will be null in the error case
*/
void * SvrHandling::threadRobotMovement(void *arg)
{
// unused parameters
@ -293,6 +300,9 @@ end:
{
std::cout << " Trajectory finished \n ";
// only save trejectories with more than 1 step
if ( currentTrajectory->getSteps()>1)
{
// each trajectory gets a new number starting from 1
static int trajcetorycount = 0;
trajcetorycount +=1;
@ -305,10 +315,12 @@ end:
currentTrajectory->saveJointToFile(filename);
}
// free the current trajectory
delete currentTrajectory;
currentTrajectory = NULL;
}
}
}

148
lwrserv/src/commands.cpp

@ -30,7 +30,6 @@
#include "commands.h"
#include "Robot.h"
#include "lwr4.h"
#include "SocketObject.h"
#include "Trajectroy.h"
#include "SvrHandling.h"
@ -88,7 +87,7 @@ void getPositionJoints(SocketObject& client, std::string& arg)
std::stringstream ss (std::stringstream::in | std::stringstream::out);
// get current joint positions from database
Robot::VecJoint jointPos = SvrData::getInstance()->getMessuredJointPos();
Robot::VecJoint jointPos = SvrData::getInstance()->getMeasuredJointPos();
// assemble command feadback
for (unsigned int i = 0 ; i < Robot::joints ; i++)
@ -98,7 +97,7 @@ void getPositionJoints(SocketObject& client, std::string& arg)
out += ss.str() + " ";
}
// send msg to client
// send message to client
client.Send(out);
}
@ -121,10 +120,10 @@ void getPositionHomRowWise(SocketObject& client, std::string& arg)
std::stringstream ss (std::stringstream::in | std::stringstream::out);
// get current Cartesian positions from database
MatCarthesian cartPos = SvrData::getInstance()->getMessuredCartPos();
MatCarthesian cartPos = SvrData::getInstance()->getMeasuredCartPos();
// assemble command feedback row wise
// leav out the 4th row cause its containing only " 0 0 0 1 "
// leave out the 4th row cause its containing only " 0 0 0 1 "
for (int row = 0; row < 3 ; row++)
{
for (int column = 0; column < 4 ; column++)
@ -135,16 +134,16 @@ void getPositionHomRowWise(SocketObject& client, std::string& arg)
}
}
// send msg to client
// send message to client
client.Send(out);
}
/**
* This function processes the request from client side to
* get the current force and torque based on the endefector
* get the current force and torque based on the end effector
* of the robot
*
* @param client connection to client which will recive the response
* @param client connection to client which will receive the response
* @param arg unused but has to be there for matching the signature
*
* @see getForceTorqueTcpHelp
@ -158,8 +157,8 @@ void getForceTorqueTcp(SocketObject& client, std::string& arg)
std::string out = "";
std::stringstream ss (std::stringstream::in | std::stringstream::out);
// get current force and torque parametes from database
VecTorque torque = SvrData::getInstance()->getMessuredForceTorque();
// get current force and torque parameters from database
VecTorque torque = SvrData::getInstance()->getMeasuredForceTorque();
// assemble command feedback
for (int i=0; i< FRI_CART_VEC; i++)
@ -169,7 +168,7 @@ void getForceTorqueTcp(SocketObject& client, std::string& arg)
out += ss.str() + " ";
}
// send msg to client
// send message to client
client.Send(out);
}
@ -178,8 +177,8 @@ void getForceTorqueTcp(SocketObject& client, std::string& arg)
* move the robot from the current position to a
* new position defined by the new joint angles
*
* @param client connection to client which will recive the response
* @param arg array containg the new joint angles from fist to last one
* @param client connection to client which will receive the response
* @param arg array containing the new joint angles from fist to last one
*
* @see movePTPJointsHelp
*/
@ -209,7 +208,7 @@ void movePTPJoints(SocketObject& client, std::string& arg)
}
// to less joint values
if (i != Robot::joints)
if (i != SvrData::getInstance()->getJoints())
{
client.Send(SVR_INVALID_ARGUMENT_COUNT);
return;
@ -240,9 +239,9 @@ void movePTPJoints(SocketObject& client, std::string& arg)
*/
void moveHomRowWiseStatus(SocketObject& client, std::string& arg)
{
double temp[15];
// set up the string buffers
std::string buf;
double temp[15];
std::stringstream ss(arg);
std::stringstream ss2f;
int argc = 0;
@ -271,7 +270,7 @@ void moveHomRowWiseStatus(SocketObject& client, std::string& arg)
return ;
}
// first part is homegenous position koordinates
// first part is homogeneous position coordinates
MatCarthesian newCartPos(0.0f, 1.0f);
for (int i=0 ;i<3; i++)
{
@ -287,8 +286,8 @@ void moveHomRowWiseStatus(SocketObject& client, std::string& arg)
configurationParameter.flip = (temp[13] == 1.0f);
configurationParameter.j1os = (temp[14] == 1.0f);
//Backward Calculation
Robot::VecJoint newJointPos = LWR4::backwardCalc(newCartPos, configurationParameter);
//backward calculation for the positions
Robot::VecJoint newJointPos = SvrData::getInstance()->getRobot()->backwardCalc(newCartPos, configurationParameter);
//check for joint range
if (!SvrData::getInstance()->checkJointRange(newJointPos))
@ -304,19 +303,23 @@ void moveHomRowWiseStatus(SocketObject& client, std::string& arg)
}
/**
* This function processes the request from client side to
* set a new percentage for the speed value.
* This function processes the request from client to
* set a new percentage for the velocity
*
* A valid range is within the interval (0,100].
*
* @param client connection to client which will receive the response
* @param arg new percentage
* @param arg new percentage velocity
*
* @see moveHomRowWiseStatusHelp
* @see setSpeedHelp
*/
void setSpeed(SocketObject& client, std::string& arg)
{
std::string buf;
float newVelocityPercentage;
int argc = 0;
// set up the string buffers
std::string buf;
std::stringstream ss(arg);
std::stringstream ss2f;
@ -357,10 +360,23 @@ void setSpeed(SocketObject& client, std::string& arg)
client.Send(SVR_TRUE_RSP);
}
/**
* This function processes the request from client to
* set a new percentage for the acceleration
*
* A valid range is within the interval (0,100].
*
* @param client connection to client which will receive the response
* @param arg new percentage for the acceleration
*
* @see setAccelHelp
*/
void setAccel(SocketObject& client, std::string& arg)
{
std::string buf;
float newAccelerationPercentage;
// setup the string buffers
std::string buf;
std::stringstream ss(arg);
std::stringstream ss2f;
int argc = 0;
@ -402,67 +418,141 @@ void setAccel(SocketObject& client, std::string& arg)
client.Send(SVR_TRUE_RSP);
}
/**
* This function starts the potential field mode.
* This mode deactivates the trajectory calculation and only
* drives the robot directly to the provided position.
* set a new percentage for the acceleration
*
* @param client connection to client which will receive the response
* @param arg unused
*
* @see startPotFieldModeHelp
*/
void startPotFieldMode(SocketObject& client, std::string& arg)
{
// unused
(void) arg;
//Set current Joint Vals
Robot::VecJoint currJoints = SvrData::getInstance()->getMessuredJointPos();
//this has to be done cause the FRI interface would not allow the
//real time mode without doing so
Robot::VecJoint currJoints = SvrData::getInstance()->getMeasuredJointPos();
moveRobotTo(currJoints);
// activate the potential filed mode
SvrData::getInstance()->setTrajectoryPotfieldMode(true);
moveRobotTo(currJoints);
// send a positive client feedback
client.Send(SVR_TRUE_RSP);
}
/**
* This function stops the potential field mode.
* This mode deactivates the trajectory calculation and only
* drives the robot directly to the provided position.
* set a new percentage for the acceleration
*
* @param client connection to client which will receive the response
* @param arg unused
*
* @see stopPotFieldModeHelp
*/
void stopPotFieldMode(SocketObject& client, std::string& arg)
{
// unused
(void) arg;
// deactivate the potential field mode
SvrData::getInstance()->setTrajectoryPotfieldMode(false);
// send a positive client feedback
client.Send(SVR_TRUE_RSP);
}
/**
* This function stops the connection to the client and
* brings the server back to the wait for client state.
*
* @param client connection to client which will receive the response
* @param arg unused
*
* @see quitHelp
*/
void quit(SocketObject& client , std::string& arg)
{
//unused
(void) arg;
// send a positive client feedback
client.Send(SVR_TRUE_RSP);
// kill the connection to this client
client.Disconnect();
}
/**
* This function sets the new trajectory type.
* The older already queued Trajectories does not get
* effected by this.
* The next move command will use this Trajectory type
* unless you are in the potential field mode.
*
* @param client connection to client which will receive the response
* @param arg sting containing the name of the new trajectory type
*
* @see setTrajectoryTypeHelp
*/
void setTrajectoryType(SocketObject& client, std::string& arg)
{
std::string buf;
enum TrajectoryType newType = TrajectoryDefault;
// convert the sting to the valid enumeration id
newType = toEnum(arg);
SvrData::getInstance()->setTrajectoryType(newType);
// send back the new/current trajectory type
client.Send("new trajectory: " + toString(newType));
// check if this new/current trajectory type does
// match the wanted state and return the feedback to the client
if (toString(newType) == arg)
client.Send(SVR_TRUE_RSP);
else
client.Send(SVR_FALSE_RSP);
}
/**
* This function returns the current trajectory type.
* The next move command will use this Trajectory type
* unless you are in the potential field mode.
*
* @param client connection to client which will receive the response
* @param arg unused
*
* @see setTrajectoryTypeHelp
*/
void getTrajectoryType(SocketObject& client, std::string& arg)
{
//unused parameter
(void) arg;
// grab the current trajectory type by enumeration id
enum TrajectoryType currType = SvrData::getInstance()->getTrajectoryType();
// send the current trajectory type after converting it to a string
client.Send("current trajectory: " + toString(currType));
// send a positive client response
client.Send(SVR_TRUE_RSP);
}
/**
*
* @param client connection to client which will recive the response
* @param arg aguments which are unused in this case
* This function returns the feedback if this server is communicating with
* a kuka lwr robot arm.
* @param client connection to client which will receive the response
* @param arg unused
*/
void isKukaLwr(SocketObject& client, std::string& arg)
{

77
lwrserv/src/program.cpp

@ -12,12 +12,23 @@
#include "Vec.h"
#include "Robot.h"
/**
* creates a matrix with x y z rotation in this order
*
* @info the pointer has to be freed by the receiving function
*
* @param x rotation in x-axis [degree]
* @param y rotation in y-axis [degree]
* @param z rotation in z-axis [degree]
* @return Rotation matrix in a float array for like homogeneous carthesian form
*/
float* abctomat(float a, float b, float c)
{
Mat4f rx;
float ca = cos(c);
float sa = sin(c);
/// create x rotation matrix
Mat4f rx;
rx(0,0) = 1.0f;
rx(1,1) = ca;
rx(1,2) = -sa;
@ -25,6 +36,7 @@ float* abctomat(float a, float b, float c)
rx(2,2) = ca;
rx(3,3) = 1.0f;
/// create y rotation matrix
Mat4f ry;
float cb = cos(b);
float sb = sin(b);
@ -35,6 +47,7 @@ float* abctomat(float a, float b, float c)
ry(2,2) = cb;
ry(3,3) = 1.0f;
/// create z rotation matrix
Mat4f rz;
float cc = cos(a);
float sc = sin(a);
@ -45,6 +58,7 @@ float* abctomat(float a, float b, float c)
rz(2,2) = 1.0f;
rz(3,3) = 1.0f;
/// combine all to one rotation matrix
Mat4f result;
Mat4f temp;
temp = rz * ry;
@ -57,8 +71,8 @@ float* abctomat(float a, float b, float c)
printMat(result);
#endif
/// convert the matrix class to a float vector
float *res = new float[12];
//TODO simple converter for mat
for (int j=0;j<3;j++)
{
for (int k=0;k<4;k++)
@ -69,6 +83,15 @@ float* abctomat(float a, float b, float c)
return res;
}
/**
* This function tries to calculate the angles
* for the given homogeneous matrix in a x-y-z rotation
*
* @info the pointer has to be freed by the receiving function
*
* @param M Matrix to convert to angles
* @return the angles in x y z rotation in exactly this order
*/
float* mattoabc(float M[12])
{
float norm;
@ -95,9 +118,23 @@ float* mattoabc(float M[12])
return abc;
}
/**
* This function converts a 12 field array conating the
* homogeneous matrix with leaving out the last row to a
* matrix class
*
* The vector has to be row wise
*
* @param vec 12 dimensional vector which should be converted
* @return a homogeneous matrix class reference
*/
Mat4f vecToMat2(float vec[12])
{
Mat4f result;
/// create a identity matrix
Mat4f result(0.0f,1.0f);
/// set the cells with the given vector
/// row wise
for (int i=0; i<3; i++)
{
for (int j=0; j<4; j++)
@ -105,10 +142,20 @@ Mat4f vecToMat2(float vec[12])
result(i,j) = (float)vec[i*4+j];
}
}
result(3,3)=1.0f;
return result;
}
/**
* This function converts a homogeneous carthesian matrix class
* to a 12 dim vector containing the same
* homogeneous matrix without the last row.
*
* The vector is row wise and the memory has to be freed
* within the receiving function.
*
* @param mat matrix class
* @return the array containing the same information like the matrix class
*/
float* matToVec2(Mat4f mat)
{
float* vec = new float[12];
@ -122,6 +169,16 @@ float* matToVec2(Mat4f mat)
return vec;
}
/**
* This function converts a 12 dim vector containing a
* homogeneous matrix without the last row to a 4
* dim vector containing the quaternion rotation
*
* The vector has to be row wise
*
* @param vec 12 dimensional vector which should be converted
* @return the quaternion rotation
*/
float* vectoquat(float vec[12])
{
float *quat = new float[4];
@ -148,6 +205,7 @@ float* vectoquat(float vec[12])
v = 1;
w = 2;
}
float r = sqrt(1+vec[(u-1)*4+(u-1)] - vec[(v-1)*4+(v-1)] - vec[(w-1)*4+(w-1)]);
quat[0] = (vec[(w-1)*4+(v-1)] - vec[(v-1)*4+(w-1)]) / (2*r);
quat[u] = r/2;
@ -157,6 +215,17 @@ float* vectoquat(float vec[12])
return quat;
}
/**
* This function converts a 12 dim vector containing a
* homogeneous matrix without the last row to a 4
* dim vector containing the quaternion rotation
*
* The vector has to be row wise
*
* @param vec 12 dimensional vector which should be converted
* @return the quaternion rotation
*/
float* quattovec(float quat[4])
{
float *vec = new float[12];

61
lwrserv/trajectory/start.m

@ -1,22 +1,55 @@
clear all
close all
filename = 'trajectory_1.csv';
M = csvread(filename);
files = dir
sampletime = 0.005
t_max = size(M,1) * sampletime;
csvfiles = dir
for i = 1:size(csvfiles,1)
t = linspace(0,t_max,size(M,1));
% check for start sequence
temp = strfind(csvfiles(i,1).name,'trajectory_')
if (1 ~= length(temp) || temp(1) ~= 1)
continue;
end
filename = csvfiles(i,1).name;
[~,M_d] = gradient( M,0.005);
[~,M_dd] = gradient( M_d,0.005);
filename
figure();
subplot(3,1,1);
plot (t,M);
subplot(3,1,2);
plot (t,M_d);
subplot(3,1,3);
plot (t,M_dd);
M = csvread(filename);
sampletime = 0.005
t_max = size(M,1) * sampletime;
t = linspace(0,t_max,size(M,1));
[~,M_d] = gradient( M,0.005);
[~,M_dd] = gradient( M_d,0.005);
% create new figure per csv
f = figure();
set(f,'name',filename,'numbertitle','off')
% plot the angles
subplot(3,1,1);
plot (t,M);
title('joint movement');
ylabel('s in [ degree ]');
xlabel('time in [ seconds ]');
% plot the velocity
subplot(3,1,2);
plot (t,M_d);
title('joint velocity ');
ylabel('v in [ degree / seconds ]');
xlabel('time in [ seconds ]');
% plot the acceleration
subplot(3,1,3);
plot (t,M_dd);
title('joint acceleration');
ylabel('a in [ degree / seconds^2 ]');
xlabel('time in [ seconds ]');
end

12501
lwrserv/trajectory/trajectory_1.csv
File diff suppressed because it is too large
View File

Loading…
Cancel
Save