[Robot] fix typo reported by spellchecker CI
- Accelaration -> Acceleration - plus some style fixes done by MSVC
This commit is contained in:
@@ -148,7 +148,7 @@ void Trajectory::deleteLast(unsigned int n)
|
|||||||
|
|
||||||
void Trajectory::generateTrajectory(void)
|
void Trajectory::generateTrajectory(void)
|
||||||
{
|
{
|
||||||
if (vpcWaypoints.size()==0)
|
if (vpcWaypoints.size() == 0)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
// delete the old and create a new one
|
// delete the old and create a new one
|
||||||
@@ -164,60 +164,60 @@ void Trajectory::generateTrajectory(void)
|
|||||||
|
|
||||||
try {
|
try {
|
||||||
// handle the first waypoint special
|
// handle the first waypoint special
|
||||||
bool first=true;
|
bool first = true;
|
||||||
|
|
||||||
for (std::vector<Waypoint*>::const_iterator it = vpcWaypoints.begin();it!=vpcWaypoints.end();++it) {
|
for (std::vector<Waypoint*>::const_iterator it = vpcWaypoints.begin(); it != vpcWaypoints.end(); ++it) {
|
||||||
if (first) {
|
if (first) {
|
||||||
Last = toFrame((*it)->EndPos);
|
Last = toFrame((*it)->EndPos);
|
||||||
first = false;
|
first = false;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
// destinct the type of movement
|
// destinct the type of movement
|
||||||
switch((*it)->Type){
|
switch ((*it)->Type) {
|
||||||
case Waypoint::LINE:
|
case Waypoint::LINE:
|
||||||
case Waypoint::PTP:{
|
case Waypoint::PTP: {
|
||||||
KDL::Frame Next = toFrame((*it)->EndPos);
|
KDL::Frame Next = toFrame((*it)->EndPos);
|
||||||
// continues the movement until no continuous waypoint or the end
|
// continues the movement until no continuous waypoint or the end
|
||||||
bool Cont = (*it)->Cont && !(it==--vpcWaypoints.end());
|
bool Cont = (*it)->Cont && !(it == --vpcWaypoints.end());
|
||||||
// start of a continue block
|
// start of a continue block
|
||||||
if (Cont && !pcRoundComp) {
|
if (Cont && !pcRoundComp) {
|
||||||
pcRoundComp.reset(new KDL::Path_RoundedComposite(3, 3,
|
pcRoundComp.reset(new KDL::Path_RoundedComposite(3, 3,
|
||||||
new KDL::RotationalInterpolation_SingleAxis()));
|
new KDL::RotationalInterpolation_SingleAxis()));
|
||||||
// the velocity of the first waypoint is used
|
// the velocity of the first waypoint is used
|
||||||
pcVelPrf.reset(new KDL::VelocityProfile_Trap((*it)->Velocity,(*it)->Accelaration));
|
pcVelPrf.reset(new KDL::VelocityProfile_Trap((*it)->Velocity, (*it)->Acceleration));
|
||||||
pcRoundComp->Add(Last);
|
pcRoundComp->Add(Last);
|
||||||
pcRoundComp->Add(Next);
|
pcRoundComp->Add(Next);
|
||||||
|
|
||||||
// continue a continues block
|
// continue a continues block
|
||||||
}
|
}
|
||||||
else if (Cont && pcRoundComp) {
|
else if (Cont && pcRoundComp) {
|
||||||
pcRoundComp->Add(Next);
|
pcRoundComp->Add(Next);
|
||||||
// end a continuous block
|
// end a continuous block
|
||||||
}
|
}
|
||||||
else if (Cont==false && pcRoundComp) {
|
else if (Cont == false && pcRoundComp) {
|
||||||
// add the last one
|
// add the last one
|
||||||
pcRoundComp->Add(Next);
|
pcRoundComp->Add(Next);
|
||||||
pcRoundComp->Finish();
|
pcRoundComp->Finish();
|
||||||
pcVelPrf->SetProfile(0,pcRoundComp->PathLength());
|
pcVelPrf->SetProfile(0, pcRoundComp->PathLength());
|
||||||
pcTrak.reset(new KDL::Trajectory_Segment(pcRoundComp.release(),pcVelPrf.release()));
|
pcTrak.reset(new KDL::Trajectory_Segment(pcRoundComp.release(), pcVelPrf.release()));
|
||||||
|
|
||||||
// normal block
|
// normal block
|
||||||
}
|
}
|
||||||
else if (Cont==false && !pcRoundComp){
|
else if (Cont == false && !pcRoundComp) {
|
||||||
KDL::Path* pcPath;
|
KDL::Path* pcPath;
|
||||||
pcPath = new KDL::Path_Line(Last,
|
pcPath = new KDL::Path_Line(Last,
|
||||||
Next,
|
Next,
|
||||||
new KDL::RotationalInterpolation_SingleAxis(),
|
new KDL::RotationalInterpolation_SingleAxis(),
|
||||||
1.0,
|
1.0,
|
||||||
true
|
true
|
||||||
);
|
);
|
||||||
|
|
||||||
pcVelPrf.reset(new KDL::VelocityProfile_Trap((*it)->Velocity,(*it)->Accelaration));
|
pcVelPrf.reset(new KDL::VelocityProfile_Trap((*it)->Velocity, (*it)->Acceleration));
|
||||||
pcVelPrf->SetProfile(0,pcPath->PathLength());
|
pcVelPrf->SetProfile(0, pcPath->PathLength());
|
||||||
pcTrak.reset(new KDL::Trajectory_Segment(pcPath,pcVelPrf.release()));
|
pcTrak.reset(new KDL::Trajectory_Segment(pcPath, pcVelPrf.release()));
|
||||||
}
|
}
|
||||||
Last = Next;
|
Last = Next;
|
||||||
break;}
|
break; }
|
||||||
case Waypoint::WAIT:
|
case Waypoint::WAIT:
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
@@ -230,7 +230,7 @@ void Trajectory::generateTrajectory(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch (KDL::Error &e) {
|
catch (KDL::Error& e) {
|
||||||
throw Base::RuntimeError(e.Description());
|
throw Base::RuntimeError(e.Description());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -69,7 +69,7 @@ TrajectoryDressUpObject::~TrajectoryDressUpObject()
|
|||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
App::DocumentObjectExecReturn *TrajectoryDressUpObject::execute(void)
|
App::DocumentObjectExecReturn* TrajectoryDressUpObject::execute(void)
|
||||||
{
|
{
|
||||||
Robot::Trajectory result;
|
Robot::Trajectory result;
|
||||||
|
|
||||||
@@ -79,39 +79,39 @@ App::DocumentObjectExecReturn *TrajectoryDressUpObject::execute(void)
|
|||||||
if (!link->getTypeId().isDerivedFrom(Robot::TrajectoryObject::getClassTypeId()))
|
if (!link->getTypeId().isDerivedFrom(Robot::TrajectoryObject::getClassTypeId()))
|
||||||
return new App::DocumentObjectExecReturn("Linked object is not a Trajectory object");
|
return new App::DocumentObjectExecReturn("Linked object is not a Trajectory object");
|
||||||
|
|
||||||
const std::vector<Waypoint*> &wps = static_cast<Robot::TrajectoryObject*>(link)->Trajectory.getValue().getWaypoints();
|
const std::vector<Waypoint*>& wps = static_cast<Robot::TrajectoryObject*>(link)->Trajectory.getValue().getWaypoints();
|
||||||
for (std::vector<Waypoint*>::const_iterator it= wps.begin();it!=wps.end();++it) {
|
for (std::vector<Waypoint*>::const_iterator it = wps.begin(); it != wps.end(); ++it) {
|
||||||
Waypoint wpt = **it;
|
Waypoint wpt = **it;
|
||||||
if(UseSpeed.getValue())
|
if (UseSpeed.getValue())
|
||||||
wpt.Velocity = Speed.getValue();
|
wpt.Velocity = Speed.getValue();
|
||||||
if(UseAcceleration.getValue())
|
if (UseAcceleration.getValue())
|
||||||
wpt.Accelaration = Acceleration.getValue();
|
wpt.Acceleration = Acceleration.getValue();
|
||||||
switch(ContType.getValue()){
|
switch (ContType.getValue()) {
|
||||||
case 0: break;
|
case 0: break;
|
||||||
case 1: wpt.Cont = true;break;
|
case 1: wpt.Cont = true; break;
|
||||||
case 2: wpt.Cont = false;break;
|
case 2: wpt.Cont = false; break;
|
||||||
default: assert(0); // must not happen!
|
default: assert(0); // must not happen!
|
||||||
}
|
}
|
||||||
switch(AddType.getValue()){
|
switch (AddType.getValue()) {
|
||||||
// do nothing
|
// do nothing
|
||||||
case 0: break;
|
case 0: break;
|
||||||
// use orientation
|
// use orientation
|
||||||
case 1:
|
case 1:
|
||||||
wpt.EndPos.setRotation(PosAdd.getValue().getRotation());
|
wpt.EndPos.setRotation(PosAdd.getValue().getRotation());
|
||||||
break;
|
break;
|
||||||
// add position
|
// add position
|
||||||
case 2:
|
case 2:
|
||||||
wpt.EndPos.setPosition(wpt.EndPos.getPosition() + PosAdd.getValue().getPosition());
|
wpt.EndPos.setPosition(wpt.EndPos.getPosition() + PosAdd.getValue().getPosition());
|
||||||
break;
|
break;
|
||||||
// add orientation
|
// add orientation
|
||||||
case 3:
|
case 3:
|
||||||
wpt.EndPos.setRotation(wpt.EndPos.getRotation() * PosAdd.getValue().getRotation());
|
wpt.EndPos.setRotation(wpt.EndPos.getRotation() * PosAdd.getValue().getRotation());
|
||||||
break;
|
break;
|
||||||
// add orientation & position
|
// add orientation & position
|
||||||
case 4:
|
case 4:
|
||||||
wpt.EndPos= wpt.EndPos * PosAdd.getValue();
|
wpt.EndPos = wpt.EndPos * PosAdd.getValue();
|
||||||
break;
|
break;
|
||||||
default: assert(0); // must not happen!
|
default: assert(0); // must not happen!
|
||||||
}
|
}
|
||||||
|
|
||||||
result.addWaypoint(wpt);
|
result.addWaypoint(wpt);
|
||||||
@@ -119,12 +119,11 @@ App::DocumentObjectExecReturn *TrajectoryDressUpObject::execute(void)
|
|||||||
|
|
||||||
// set the resulting Trajectory to the object
|
// set the resulting Trajectory to the object
|
||||||
Trajectory.setValue(result);
|
Trajectory.setValue(result);
|
||||||
|
|
||||||
return App::DocumentObject::StdReturn;
|
return App::DocumentObject::StdReturn;
|
||||||
}
|
}
|
||||||
|
|
||||||
void TrajectoryDressUpObject::onChanged(const Property* prop)
|
void TrajectoryDressUpObject::onChanged(const Property* prop)
|
||||||
{
|
{
|
||||||
|
|
||||||
App::GeoFeature::onChanged(prop);
|
App::GeoFeature::onChanged(prop);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -60,7 +60,7 @@ Waypoint::Waypoint(const char* name,
|
|||||||
const Base::Placement &endPos,
|
const Base::Placement &endPos,
|
||||||
WaypointType type,
|
WaypointType type,
|
||||||
float velocity,
|
float velocity,
|
||||||
float accelaration,
|
float acceleration,
|
||||||
bool cont,
|
bool cont,
|
||||||
unsigned int tool,
|
unsigned int tool,
|
||||||
unsigned int base)
|
unsigned int base)
|
||||||
@@ -68,7 +68,7 @@ Waypoint::Waypoint(const char* name,
|
|||||||
: Name(name)
|
: Name(name)
|
||||||
, Type(type)
|
, Type(type)
|
||||||
, Velocity(velocity)
|
, Velocity(velocity)
|
||||||
, Accelaration(accelaration)
|
, Acceleration(acceleration)
|
||||||
, Cont(cont)
|
, Cont(cont)
|
||||||
, Tool(tool)
|
, Tool(tool)
|
||||||
, Base(base)
|
, Base(base)
|
||||||
@@ -79,7 +79,7 @@ Waypoint::Waypoint(const char* name,
|
|||||||
Waypoint::Waypoint()
|
Waypoint::Waypoint()
|
||||||
: Type(UNDEF)
|
: Type(UNDEF)
|
||||||
, Velocity(1000.0)
|
, Velocity(1000.0)
|
||||||
, Accelaration(100.0)
|
, Acceleration(100.0)
|
||||||
, Cont(false)
|
, Cont(false)
|
||||||
, Tool(0)
|
, Tool(0)
|
||||||
, Base(0)
|
, Base(0)
|
||||||
@@ -107,7 +107,7 @@ void Waypoint::Save (Writer &writer) const
|
|||||||
<< "Q2=\"" << EndPos.getRotation()[2] << "\" "
|
<< "Q2=\"" << EndPos.getRotation()[2] << "\" "
|
||||||
<< "Q3=\"" << EndPos.getRotation()[3] << "\" "
|
<< "Q3=\"" << EndPos.getRotation()[3] << "\" "
|
||||||
<< "vel=\"" << Velocity << "\" "
|
<< "vel=\"" << Velocity << "\" "
|
||||||
<< "acc=\"" << Accelaration << "\" "
|
<< "acc=\"" << Acceleration << "\" "
|
||||||
<< "cont=\"" << int((Cont)?1:0) << "\" "
|
<< "cont=\"" << int((Cont)?1:0) << "\" "
|
||||||
<< "tool=\"" << Tool << "\" "
|
<< "tool=\"" << Tool << "\" "
|
||||||
<< "base=\"" << Base << "\" ";
|
<< "base=\"" << Base << "\" ";
|
||||||
@@ -139,7 +139,7 @@ void Waypoint::Restore(XMLReader &reader)
|
|||||||
reader.getAttributeAsFloat("Q3")));
|
reader.getAttributeAsFloat("Q3")));
|
||||||
|
|
||||||
Velocity = (float) reader.getAttributeAsFloat("vel");
|
Velocity = (float) reader.getAttributeAsFloat("vel");
|
||||||
Accelaration = (float) reader.getAttributeAsFloat("acc");
|
Acceleration = (float) reader.getAttributeAsFloat("acc");
|
||||||
Cont = (reader.getAttributeAsInteger("cont") != 0)?true:false;
|
Cont = (reader.getAttributeAsInteger("cont") != 0)?true:false;
|
||||||
Tool = reader.getAttributeAsInteger("tool");
|
Tool = reader.getAttributeAsInteger("tool");
|
||||||
Base = reader.getAttributeAsInteger("base");
|
Base = reader.getAttributeAsInteger("base");
|
||||||
|
|||||||
@@ -50,27 +50,27 @@ public:
|
|||||||
|
|
||||||
Waypoint();
|
Waypoint();
|
||||||
/// full constructor
|
/// full constructor
|
||||||
Waypoint(const char* name,
|
Waypoint(const char* name,
|
||||||
const Base::Placement &endPos,
|
const Base::Placement& endPos,
|
||||||
WaypointType type=Waypoint::LINE,
|
WaypointType type = Waypoint::LINE,
|
||||||
float velocity=2000.0,
|
float velocity = 2000.0,
|
||||||
float accelaration=100.0,
|
float acceleration = 100.0,
|
||||||
bool cont=false,
|
bool cont = false,
|
||||||
unsigned int tool=0,
|
unsigned int tool = 0,
|
||||||
unsigned int base = 0);
|
unsigned int base = 0);
|
||||||
|
|
||||||
~Waypoint();
|
~Waypoint();
|
||||||
|
|
||||||
// from base class
|
// from base class
|
||||||
virtual unsigned int getMemSize (void) const;
|
virtual unsigned int getMemSize(void) const;
|
||||||
virtual void Save (Base::Writer &/*writer*/) const;
|
virtual void Save(Base::Writer& /*writer*/) const;
|
||||||
virtual void Restore(Base::XMLReader &/*reader*/);
|
virtual void Restore(Base::XMLReader& /*reader*/);
|
||||||
|
|
||||||
|
|
||||||
std::string Name;
|
std::string Name;
|
||||||
WaypointType Type;
|
WaypointType Type;
|
||||||
float Velocity;
|
float Velocity;
|
||||||
float Accelaration;
|
float Acceleration;
|
||||||
bool Cont;
|
bool Cont;
|
||||||
unsigned int Tool,Base;
|
unsigned int Tool,Base;
|
||||||
Base::Placement EndPos;
|
Base::Placement EndPos;
|
||||||
|
|||||||
@@ -83,60 +83,60 @@ PyObject *WaypointPy::PyMake(struct _typeobject *, PyObject *, PyObject *) // P
|
|||||||
// constructor method
|
// constructor method
|
||||||
int WaypointPy::PyInit(PyObject* args, PyObject* kwd)
|
int WaypointPy::PyInit(PyObject* args, PyObject* kwd)
|
||||||
{
|
{
|
||||||
PyObject *pos;
|
PyObject* pos;
|
||||||
char *name="P";
|
char* name = "P";
|
||||||
char *type = "PTP";
|
char* type = "PTP";
|
||||||
PyObject *vel = 0;
|
PyObject* vel = 0;
|
||||||
PyObject *acc = 0;
|
PyObject* acc = 0;
|
||||||
int cont = 0;
|
int cont = 0;
|
||||||
int tool=0;
|
int tool = 0;
|
||||||
int base=0;
|
int base = 0;
|
||||||
|
|
||||||
static char *kwlist[] = {"Pos", "type","name", "vel", "cont", "tool", "base", "acc" ,NULL};
|
static char* kwlist[] = { "Pos", "type","name", "vel", "cont", "tool", "base", "acc" ,NULL };
|
||||||
|
|
||||||
if (!PyArg_ParseTupleAndKeywords(args, kwd, "O!|ssOiiiO", kwlist,
|
if (!PyArg_ParseTupleAndKeywords(args, kwd, "O!|ssOiiiO", kwlist,
|
||||||
&(Base::PlacementPy::Type), &pos, // the placement object
|
&(Base::PlacementPy::Type), &pos, // the placement object
|
||||||
&type, &name, &vel, &cont, &tool, &base, &acc ))
|
&type, &name, &vel, &cont, &tool, &base, &acc))
|
||||||
return -1;
|
return -1;
|
||||||
|
|
||||||
Base::Placement TempPos = *static_cast<Base::PlacementPy*>(pos)->getPlacementPtr();
|
Base::Placement TempPos = *static_cast<Base::PlacementPy*>(pos)->getPlacementPtr();
|
||||||
getWaypointPtr()->EndPos = TempPos;
|
getWaypointPtr()->EndPos = TempPos;
|
||||||
getWaypointPtr()->Name = name;
|
getWaypointPtr()->Name = name;
|
||||||
std::string typeStr(type);
|
std::string typeStr(type);
|
||||||
if(typeStr=="PTP")
|
if (typeStr == "PTP")
|
||||||
getWaypointPtr()->Type = Waypoint::PTP;
|
getWaypointPtr()->Type = Waypoint::PTP;
|
||||||
else if(typeStr=="LIN")
|
else if (typeStr == "LIN")
|
||||||
getWaypointPtr()->Type = Waypoint::LINE;
|
getWaypointPtr()->Type = Waypoint::LINE;
|
||||||
else if(typeStr=="CIRC")
|
else if (typeStr == "CIRC")
|
||||||
getWaypointPtr()->Type = Waypoint::CIRC;
|
getWaypointPtr()->Type = Waypoint::CIRC;
|
||||||
else if(typeStr=="WAIT")
|
else if (typeStr == "WAIT")
|
||||||
getWaypointPtr()->Type = Waypoint::WAIT;
|
getWaypointPtr()->Type = Waypoint::WAIT;
|
||||||
else
|
else
|
||||||
getWaypointPtr()->Type = Waypoint::UNDEF;
|
getWaypointPtr()->Type = Waypoint::UNDEF;
|
||||||
|
|
||||||
if(vel == 0)
|
if (vel == 0)
|
||||||
switch (getWaypointPtr()->Type){
|
switch (getWaypointPtr()->Type) {
|
||||||
case Waypoint::PTP:
|
case Waypoint::PTP:
|
||||||
getWaypointPtr()->Velocity = 100;
|
getWaypointPtr()->Velocity = 100;
|
||||||
break;
|
break;
|
||||||
case Waypoint::LINE:
|
case Waypoint::LINE:
|
||||||
getWaypointPtr()->Velocity = 2000;
|
getWaypointPtr()->Velocity = 2000;
|
||||||
break;
|
break;
|
||||||
case Waypoint::CIRC:
|
case Waypoint::CIRC:
|
||||||
getWaypointPtr()->Velocity = 2000;
|
getWaypointPtr()->Velocity = 2000;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
getWaypointPtr()->Velocity = 0;
|
getWaypointPtr()->Velocity = 0;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
getWaypointPtr()->Velocity = Base::UnitsApi::toDouble(vel,Base::Unit::Velocity);
|
getWaypointPtr()->Velocity = Base::UnitsApi::toDouble(vel, Base::Unit::Velocity);
|
||||||
getWaypointPtr()->Cont = cont?true:false;
|
getWaypointPtr()->Cont = cont ? true : false;
|
||||||
getWaypointPtr()->Tool = tool;
|
getWaypointPtr()->Tool = tool;
|
||||||
getWaypointPtr()->Base = base;
|
getWaypointPtr()->Base = base;
|
||||||
if(acc == 0)
|
if (acc == 0)
|
||||||
getWaypointPtr()->Accelaration = 100;
|
getWaypointPtr()->Acceleration = 100;
|
||||||
else
|
else
|
||||||
getWaypointPtr()->Accelaration = Base::UnitsApi::toDouble(acc,Base::Unit::Acceleration);
|
getWaypointPtr()->Acceleration = Base::UnitsApi::toDouble(acc, Base::Unit::Acceleration);
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,111 +1,111 @@
|
|||||||
// Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
|
// Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
|
||||||
|
|
||||||
// Version: 1.0
|
// Version: 1.0
|
||||||
// Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
|
// Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
|
||||||
// Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
|
// Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
|
||||||
// URL: http://www.orocos.org/kdl
|
// URL: http://www.orocos.org/kdl
|
||||||
|
|
||||||
// This library is free software; you can redistribute it and/or
|
// This library is free software; you can redistribute it and/or
|
||||||
// modify it under the terms of the GNU Lesser General Public
|
// modify it under the terms of the GNU Lesser General Public
|
||||||
// License as published by the Free Software Foundation; either
|
// License as published by the Free Software Foundation; either
|
||||||
// version 2.1 of the License, or (at your option) any later version.
|
// version 2.1 of the License, or (at your option) any later version.
|
||||||
|
|
||||||
// This library is distributed in the hope that it will be useful,
|
// This library is distributed in the hope that it will be useful,
|
||||||
// but WITHOUT ANY WARRANTY; without even the implied warranty of
|
// but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||||
// Lesser General Public License for more details.
|
// Lesser General Public License for more details.
|
||||||
|
|
||||||
// You should have received a copy of the GNU Lesser General Public
|
// You should have received a copy of the GNU Lesser General Public
|
||||||
// License along with this library; if not, write to the Free Software
|
// License along with this library; if not, write to the Free Software
|
||||||
// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||||
|
|
||||||
#ifndef KDL_CHAIN_FKSOLVER_HPP
|
#ifndef KDL_CHAIN_FKSOLVER_HPP
|
||||||
#define KDL_CHAIN_FKSOLVER_HPP
|
#define KDL_CHAIN_FKSOLVER_HPP
|
||||||
|
|
||||||
#include "chain.hpp"
|
#include "chain.hpp"
|
||||||
#include "framevel.hpp"
|
#include "framevel.hpp"
|
||||||
#include "frameacc.hpp"
|
#include "frameacc.hpp"
|
||||||
#include "jntarray.hpp"
|
#include "jntarray.hpp"
|
||||||
#include "jntarrayvel.hpp"
|
#include "jntarrayvel.hpp"
|
||||||
#include "jntarrayacc.hpp"
|
#include "jntarrayacc.hpp"
|
||||||
#include "solveri.hpp"
|
#include "solveri.hpp"
|
||||||
|
|
||||||
namespace KDL {
|
namespace KDL {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* \brief This <strong>abstract</strong> class encapsulates a
|
* \brief This <strong>abstract</strong> class encapsulates a
|
||||||
* solver for the forward position kinematics for a KDL::Chain.
|
* solver for the forward position kinematics for a KDL::Chain.
|
||||||
*
|
*
|
||||||
* @ingroup KinematicFamily
|
* @ingroup KinematicFamily
|
||||||
*/
|
*/
|
||||||
|
|
||||||
//Forward definition
|
//Forward definition
|
||||||
class ChainFkSolverPos : public KDL::SolverI {
|
class ChainFkSolverPos : public KDL::SolverI {
|
||||||
public:
|
public:
|
||||||
/**
|
/**
|
||||||
* Calculate forward position kinematics for a KDL::Chain,
|
* Calculate forward position kinematics for a KDL::Chain,
|
||||||
* from joint coordinates to cartesian pose.
|
* from joint coordinates to cartesian pose.
|
||||||
*
|
*
|
||||||
* @param q_in input joint coordinates
|
* @param q_in input joint coordinates
|
||||||
* @param p_out reference to output cartesian pose
|
* @param p_out reference to output cartesian pose
|
||||||
* @param segmentNr default to -1
|
* @param segmentNr default to -1
|
||||||
*
|
*
|
||||||
* @return if < 0 something went wrong
|
* @return if < 0 something went wrong
|
||||||
*/
|
*/
|
||||||
virtual int JntToCart(const JntArray& q_in, Frame& p_out,int segmentNr=-1)=0;
|
virtual int JntToCart(const JntArray& q_in, Frame& p_out,int segmentNr=-1)=0;
|
||||||
virtual ~ChainFkSolverPos(){};
|
virtual ~ChainFkSolverPos(){};
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* \brief This <strong>abstract</strong> class encapsulates a solver
|
* \brief This <strong>abstract</strong> class encapsulates a solver
|
||||||
* for the forward velocity kinematics for a KDL::Chain.
|
* for the forward velocity kinematics for a KDL::Chain.
|
||||||
*
|
*
|
||||||
* @ingroup KinematicFamily
|
* @ingroup KinematicFamily
|
||||||
*/
|
*/
|
||||||
class ChainFkSolverVel : public KDL::SolverI {
|
class ChainFkSolverVel : public KDL::SolverI {
|
||||||
public:
|
public:
|
||||||
/**
|
/**
|
||||||
* Calculate forward position and velocity kinematics, from
|
* Calculate forward position and velocity kinematics, from
|
||||||
* joint coordinates to cartesian coordinates.
|
* joint coordinates to cartesian coordinates.
|
||||||
*
|
*
|
||||||
* @param q_in input joint coordinates (position and velocity)
|
* @param q_in input joint coordinates (position and velocity)
|
||||||
* @param out output cartesian coordinates (position and velocity)
|
* @param out output cartesian coordinates (position and velocity)
|
||||||
* @param segmentNr default to -1
|
* @param segmentNr default to -1
|
||||||
*
|
*
|
||||||
* @return if < 0 something went wrong
|
* @return if < 0 something went wrong
|
||||||
*/
|
*/
|
||||||
virtual int JntToCart(const JntArrayVel& q_in, FrameVel& out,int segmentNr=-1)=0;
|
virtual int JntToCart(const JntArrayVel& q_in, FrameVel& out,int segmentNr=-1)=0;
|
||||||
|
|
||||||
virtual ~ChainFkSolverVel(){};
|
virtual ~ChainFkSolverVel(){};
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* \brief This <strong>abstract</strong> class encapsulates a solver
|
* \brief This <strong>abstract</strong> class encapsulates a solver
|
||||||
* for the forward acceleration kinematics for a KDL::Chain.
|
* for the forward acceleration kinematics for a KDL::Chain.
|
||||||
*
|
*
|
||||||
* @ingroup KinematicFamily
|
* @ingroup KinematicFamily
|
||||||
*/
|
*/
|
||||||
|
|
||||||
class ChainFkSolverAcc : public KDL::SolverI {
|
class ChainFkSolverAcc : public KDL::SolverI {
|
||||||
public:
|
public:
|
||||||
/**
|
/**
|
||||||
* Calculate forward position, velocity and accelaration
|
* Calculate forward position, velocity and acceleration
|
||||||
* kinematics, from joint coordinates to cartesian coordinates
|
* kinematics, from joint coordinates to cartesian coordinates
|
||||||
*
|
*
|
||||||
* @param q_in input joint coordinates (position, velocity and
|
* @param q_in input joint coordinates (position, velocity and
|
||||||
* acceleration
|
* acceleration
|
||||||
* @param out output cartesian coordinates (position, velocity
|
* @param out output cartesian coordinates (position, velocity
|
||||||
* and acceleration
|
* and acceleration
|
||||||
* @param segmentNr default to -1
|
* @param segmentNr default to -1
|
||||||
*
|
*
|
||||||
* @return if < 0 something went wrong
|
* @return if < 0 something went wrong
|
||||||
*/
|
*/
|
||||||
virtual int JntToCart(const JntArrayAcc& q_in, FrameAcc& out,int segmentNr=-1)=0;
|
virtual int JntToCart(const JntArrayAcc& q_in, FrameAcc& out,int segmentNr=-1)=0;
|
||||||
|
|
||||||
virtual ~ChainFkSolverAcc()=0;
|
virtual ~ChainFkSolverAcc()=0;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
}//end of namespace KDL
|
}//end of namespace KDL
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
@@ -1,110 +1,110 @@
|
|||||||
// Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
|
// Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
|
||||||
// Copyright (C) 2008 Julia Jesse
|
// Copyright (C) 2008 Julia Jesse
|
||||||
|
|
||||||
// Version: 1.0
|
// Version: 1.0
|
||||||
// Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
|
// Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
|
||||||
// Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
|
// Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
|
||||||
// URL: http://www.orocos.org/kdl
|
// URL: http://www.orocos.org/kdl
|
||||||
|
|
||||||
// This library is free software; you can redistribute it and/or
|
// This library is free software; you can redistribute it and/or
|
||||||
// modify it under the terms of the GNU Lesser General Public
|
// modify it under the terms of the GNU Lesser General Public
|
||||||
// License as published by the Free Software Foundation; either
|
// License as published by the Free Software Foundation; either
|
||||||
// version 2.1 of the License, or (at your option) any later version.
|
// version 2.1 of the License, or (at your option) any later version.
|
||||||
|
|
||||||
// This library is distributed in the hope that it will be useful,
|
// This library is distributed in the hope that it will be useful,
|
||||||
// but WITHOUT ANY WARRANTY; without even the implied warranty of
|
// but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||||
// Lesser General Public License for more details.
|
// Lesser General Public License for more details.
|
||||||
|
|
||||||
// You should have received a copy of the GNU Lesser General Public
|
// You should have received a copy of the GNU Lesser General Public
|
||||||
// License along with this library; if not, write to the Free Software
|
// License along with this library; if not, write to the Free Software
|
||||||
// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||||
|
|
||||||
#ifndef KDL_TREE_FKSOLVER_HPP
|
#ifndef KDL_TREE_FKSOLVER_HPP
|
||||||
#define KDL_TREE_FKSOLVER_HPP
|
#define KDL_TREE_FKSOLVER_HPP
|
||||||
|
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|
||||||
#include "tree.hpp"
|
#include "tree.hpp"
|
||||||
//#include "framevel.hpp"
|
//#include "framevel.hpp"
|
||||||
//#include "frameacc.hpp"
|
//#include "frameacc.hpp"
|
||||||
#include "jntarray.hpp"
|
#include "jntarray.hpp"
|
||||||
//#include "jntarrayvel.hpp"
|
//#include "jntarrayvel.hpp"
|
||||||
//#include "jntarrayacc.hpp"
|
//#include "jntarrayacc.hpp"
|
||||||
|
|
||||||
namespace KDL {
|
namespace KDL {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* \brief This <strong>abstract</strong> class encapsulates a
|
* \brief This <strong>abstract</strong> class encapsulates a
|
||||||
* solver for the forward position kinematics for a KDL::Tree.
|
* solver for the forward position kinematics for a KDL::Tree.
|
||||||
*
|
*
|
||||||
* @ingroup KinematicFamily
|
* @ingroup KinematicFamily
|
||||||
*/
|
*/
|
||||||
|
|
||||||
//Forward definition
|
//Forward definition
|
||||||
class TreeFkSolverPos {
|
class TreeFkSolverPos {
|
||||||
public:
|
public:
|
||||||
/**
|
/**
|
||||||
* Calculate forward position kinematics for a KDL::Tree,
|
* Calculate forward position kinematics for a KDL::Tree,
|
||||||
* from joint coordinates to cartesian pose.
|
* from joint coordinates to cartesian pose.
|
||||||
*
|
*
|
||||||
* @param q_in input joint coordinates
|
* @param q_in input joint coordinates
|
||||||
* @param p_out reference to output cartesian pose
|
* @param p_out reference to output cartesian pose
|
||||||
* @param segmentName
|
* @param segmentName
|
||||||
* @return if < 0 something went wrong
|
* @return if < 0 something went wrong
|
||||||
*/
|
*/
|
||||||
virtual int JntToCart(const JntArray& q_in, Frame& p_out, std::string segmentName)=0;
|
virtual int JntToCart(const JntArray& q_in, Frame& p_out, std::string segmentName)=0;
|
||||||
virtual ~TreeFkSolverPos(){};
|
virtual ~TreeFkSolverPos(){};
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* \brief This <strong>abstract</strong> class encapsulates a solver
|
* \brief This <strong>abstract</strong> class encapsulates a solver
|
||||||
* for the forward velocity kinematics for a KDL::Tree.
|
* for the forward velocity kinematics for a KDL::Tree.
|
||||||
*
|
*
|
||||||
* @ingroup KinematicFamily
|
* @ingroup KinematicFamily
|
||||||
*/
|
*/
|
||||||
// class TreeFkSolverVel {
|
// class TreeFkSolverVel {
|
||||||
// public:
|
// public:
|
||||||
/**
|
/**
|
||||||
* Calculate forward position and velocity kinematics, from
|
* Calculate forward position and velocity kinematics, from
|
||||||
* joint coordinates to cartesian coordinates.
|
* joint coordinates to cartesian coordinates.
|
||||||
*
|
*
|
||||||
* @param q_in input joint coordinates (position and velocity)
|
* @param q_in input joint coordinates (position and velocity)
|
||||||
* @param out output cartesian coordinates (position and velocity)
|
* @param out output cartesian coordinates (position and velocity)
|
||||||
*
|
*
|
||||||
* @return if < 0 something went wrong
|
* @return if < 0 something went wrong
|
||||||
*/
|
*/
|
||||||
// virtual int JntToCart(const JntArrayVel& q_in, FrameVel& out,int segmentNr=-1)=0;
|
// virtual int JntToCart(const JntArrayVel& q_in, FrameVel& out,int segmentNr=-1)=0;
|
||||||
|
|
||||||
// virtual ~TreeFkSolverVel(){};
|
// virtual ~TreeFkSolverVel(){};
|
||||||
// };
|
// };
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* \brief This <strong>abstract</strong> class encapsulates a solver
|
* \brief This <strong>abstract</strong> class encapsulates a solver
|
||||||
* for the forward acceleration kinematics for a KDL::Tree.
|
* for the forward acceleration kinematics for a KDL::Tree.
|
||||||
*
|
*
|
||||||
* @ingroup KinematicFamily
|
* @ingroup KinematicFamily
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// class TreeFkSolverAcc {
|
// class TreeFkSolverAcc {
|
||||||
// public:
|
// public:
|
||||||
/**
|
/**
|
||||||
* Calculate forward position, velocity and accelaration
|
* Calculate forward position, velocity and acceleration
|
||||||
* kinematics, from joint coordinates to cartesian coordinates
|
* kinematics, from joint coordinates to cartesian coordinates
|
||||||
*
|
*
|
||||||
* @param q_in input joint coordinates (position, velocity and
|
* @param q_in input joint coordinates (position, velocity and
|
||||||
* acceleration
|
* acceleration
|
||||||
@param out output cartesian coordinates (position, velocity
|
@param out output cartesian coordinates (position, velocity
|
||||||
* and acceleration
|
* and acceleration
|
||||||
*
|
*
|
||||||
* @return if < 0 something went wrong
|
* @return if < 0 something went wrong
|
||||||
*/
|
*/
|
||||||
// virtual int JntToCart(const JntArrayAcc& q_in, FrameAcc& out,int segmentNr=-1)=0;
|
// virtual int JntToCart(const JntArrayAcc& q_in, FrameAcc& out,int segmentNr=-1)=0;
|
||||||
|
|
||||||
// virtual ~TreeFkSolverAcc()=0;
|
// virtual ~TreeFkSolverAcc()=0;
|
||||||
// };
|
// };
|
||||||
|
|
||||||
|
|
||||||
}//end of namespace KDL
|
}//end of namespace KDL
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
@@ -92,7 +92,7 @@ PyMOD_INIT_FUNC(RobotGui)
|
|||||||
// default Cintinuity is off
|
// default Cintinuity is off
|
||||||
Base::Interpreter().runString("_DefCont = False");
|
Base::Interpreter().runString("_DefCont = False");
|
||||||
// default Cintinuity is off
|
// default Cintinuity is off
|
||||||
Base::Interpreter().runString("_DefAccelaration = '1 m/s^2'");
|
Base::Interpreter().runString("_DefAcceleration = '1 m/s^2'");
|
||||||
// default orientation of a waypoint if no other constraint
|
// default orientation of a waypoint if no other constraint
|
||||||
Base::Interpreter().runString("_DefOrientation = FreeCAD.Rotation()");
|
Base::Interpreter().runString("_DefOrientation = FreeCAD.Rotation()");
|
||||||
// default displacement while e.g. picking
|
// default displacement while e.g. picking
|
||||||
|
|||||||
@@ -130,7 +130,7 @@ void CmdRobotInsertWaypoint::activated(int)
|
|||||||
std::string TrakName = pcTrajectoryObject->getNameInDocument();
|
std::string TrakName = pcTrajectoryObject->getNameInDocument();
|
||||||
|
|
||||||
openCommand("Insert waypoint");
|
openCommand("Insert waypoint");
|
||||||
doCommand(Doc,"App.activeDocument().%s.Trajectory = App.activeDocument().%s.Trajectory.insertWaypoints(Robot.Waypoint(App.activeDocument().%s.Tcp.multiply(App.activeDocument().%s.Tool),type='LIN',name='Pt',vel=_DefSpeed,cont=_DefCont,acc=_DefAccelaration,tool=1))",TrakName.c_str(),TrakName.c_str(),RoboName.c_str(),RoboName.c_str());
|
doCommand(Doc,"App.activeDocument().%s.Trajectory = App.activeDocument().%s.Trajectory.insertWaypoints(Robot.Waypoint(App.activeDocument().%s.Tcp.multiply(App.activeDocument().%s.Tool),type='LIN',name='Pt',vel=_DefSpeed,cont=_DefCont,acc=_DefAcceleration,tool=1))",TrakName.c_str(),TrakName.c_str(),RoboName.c_str(),RoboName.c_str());
|
||||||
updateActive();
|
updateActive();
|
||||||
commitCommand();
|
commitCommand();
|
||||||
|
|
||||||
@@ -194,7 +194,7 @@ void CmdRobotInsertWaypointPreselect::activated(int)
|
|||||||
}
|
}
|
||||||
|
|
||||||
openCommand("Insert waypoint");
|
openCommand("Insert waypoint");
|
||||||
doCommand(Doc,"App.activeDocument().%s.Trajectory = App.activeDocument().%s.Trajectory.insertWaypoints(Robot.Waypoint(FreeCAD.Placement(FreeCAD.Vector(%f,%f,%f)+_DefDisplacement,_DefOrientation),type='LIN',name='Pt',vel=_DefSpeed,cont=_DefCont,acc=_DefAccelaration,tool=1))",TrakName.c_str(),TrakName.c_str(),x,y,z);
|
doCommand(Doc,"App.activeDocument().%s.Trajectory = App.activeDocument().%s.Trajectory.insertWaypoints(Robot.Waypoint(FreeCAD.Placement(FreeCAD.Vector(%f,%f,%f)+_DefDisplacement,_DefOrientation),type='LIN',name='Pt',vel=_DefSpeed,cont=_DefCont,acc=_DefAcceleration,tool=1))",TrakName.c_str(),TrakName.c_str(),x,y,z);
|
||||||
updateActive();
|
updateActive();
|
||||||
commitCommand();
|
commitCommand();
|
||||||
|
|
||||||
@@ -286,7 +286,7 @@ void CmdRobotSetDefaultValues::activated(int)
|
|||||||
QObject::tr("acceleration: (e.g. 1 m/s^2 or 3 cm/s^2)"), QLineEdit::Normal,
|
QObject::tr("acceleration: (e.g. 1 m/s^2 or 3 cm/s^2)"), QLineEdit::Normal,
|
||||||
QString::fromLatin1("1 m/s^2"), &ok, Qt::MSWindowsFixedSizeDialogHint);
|
QString::fromLatin1("1 m/s^2"), &ok, Qt::MSWindowsFixedSizeDialogHint);
|
||||||
if ( ok && !text.isEmpty() ) {
|
if ( ok && !text.isEmpty() ) {
|
||||||
doCommand(Doc,"_DefAccelaration = '%s'",text.toLatin1().constData());
|
doCommand(Doc,"_DefAcceleration = '%s'",text.toLatin1().constData());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -81,7 +81,7 @@ TaskTrajectory::TaskTrajectory(Robot::RobotObject *pcRobotObject,Robot::Trajecto
|
|||||||
else
|
else
|
||||||
ui->trajectoryTable->setItem(i, 2, new QTableWidgetItem(QString::fromLatin1("-")));
|
ui->trajectoryTable->setItem(i, 2, new QTableWidgetItem(QString::fromLatin1("-")));
|
||||||
ui->trajectoryTable->setItem(i, 3, new QTableWidgetItem(QString::number(pt.Velocity)));
|
ui->trajectoryTable->setItem(i, 3, new QTableWidgetItem(QString::number(pt.Velocity)));
|
||||||
ui->trajectoryTable->setItem(i, 4, new QTableWidgetItem(QString::number(pt.Accelaration)));
|
ui->trajectoryTable->setItem(i, 4, new QTableWidgetItem(QString::number(pt.Acceleration)));
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -79,7 +79,7 @@ TrajectorySimulate::TrajectorySimulate(Robot::RobotObject *pcRobotObject,Robot::
|
|||||||
else
|
else
|
||||||
ui->trajectoryTable->setItem(i, 2, new QTableWidgetItem(QString::fromLatin1("-")));
|
ui->trajectoryTable->setItem(i, 2, new QTableWidgetItem(QString::fromLatin1("-")));
|
||||||
ui->trajectoryTable->setItem(i, 3, new QTableWidgetItem(QString::number(pt.Velocity)));
|
ui->trajectoryTable->setItem(i, 3, new QTableWidgetItem(QString::number(pt.Velocity)));
|
||||||
ui->trajectoryTable->setItem(i, 4, new QTableWidgetItem(QString::number(pt.Accelaration)));
|
ui->trajectoryTable->setItem(i, 4, new QTableWidgetItem(QString::number(pt.Acceleration)));
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user