Skip to content

Commit 547bc2a

Browse files
committed
[device]
* Change naming convention of CONTROL_TYPE. * Add function setNoIntegration in the SoTAbstract External Interface * Move robotState signal from sot-hrp2-device to sot-core. * Create additional signal robotVelocity to map the velocity sensor data from robot/simulators
1 parent 1e17972 commit 547bc2a

File tree

3 files changed

+41
-23
lines changed

3 files changed

+41
-23
lines changed

include/sot/core/abstract-sot-external-interface.hh

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,7 @@ namespace dynamicgraph {
7171

7272
virtual void getControl(std::map<std::string,ControlValues> &)=0;
7373
virtual void setSecondOrderIntegration(void)=0;
74+
virtual void setNoIntegration(void)=0;
7475
};
7576
}
7677
}

include/sot/core/device.hh

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -40,15 +40,15 @@ namespace dynamicgraph {
4040
/// Define the type of input expected by the robot
4141
enum ControlInput
4242
{
43-
CONTROL_INPUT_POSITION=0,
44-
CONTROL_INPUT_VELOCITY=1,
45-
CONTROL_INPUT_ACCELERATION=2,
43+
CONTROL_INPUT_NO_INTEGRATION=0,
44+
CONTROL_INPUT_ONE_INTEGRATION=1,
45+
CONTROL_INPUT_TWO_INTEGRATION=2,
4646
CONTROL_INPUT_SIZE=3
4747
};
4848

4949
const std::string ControlInput_s[] =
5050
{
51-
"position", "velocity", "acceleration"
51+
"noInteg", "oneInteg", "twoInteg"
5252
};
5353

5454
/* --------------------------------------------------------------------- */
@@ -93,6 +93,7 @@ namespace dynamicgraph {
9393
void setVelocitySize(const unsigned int& size);
9494
virtual void setVelocity(const dg::Vector & vel);
9595
virtual void setSecondOrderIntegration();
96+
virtual void setNoIntegration();
9697
virtual void setControlInputType(const std::string& cit);
9798
virtual void increment(const double & dt = 5e-2);
9899

@@ -110,6 +111,12 @@ namespace dynamicgraph {
110111
dynamicgraph::SignalPtr<dg::Vector,int> zmpSIN;
111112

112113
dynamicgraph::Signal<dg::Vector,int> stateSOUT;
114+
/// This corresponds to the real encoders values and take into
115+
/// account the stabilization step. Therefore, this usually
116+
/// does *not* match the state control input signal.
117+
///
118+
dynamicgraph::Signal<dg::Vector, int> robotState_;
119+
dynamicgraph::Signal<dg::Vector, int> robotVelocity_;
113120
dynamicgraph::Signal<dg::Vector,int> velocitySOUT;
114121
dynamicgraph::Signal<MatrixRotation,int> attitudeSOUT;
115122
dynamicgraph::Signal<dg::Vector,int>* forcesSOUT[4];

src/tools/device.cpp

Lines changed: 29 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -115,8 +115,10 @@ Device::
115115
Device( const std::string& n )
116116
:Entity(n)
117117
,state_(6)
118+
,robotState_("Device(" + n + ")::output(vector)::robotState")
119+
,robotVelocity_("Device(" + n + ")::output(vector)::robotVelocity")
118120
,vel_controlInit_(false)
119-
,controlInputType_(CONTROL_INPUT_VELOCITY)
121+
,controlInputType_(CONTROL_INPUT_ONE_INTEGRATION)
120122
,controlSIN( NULL,"Device("+n+")::input(double)::control" )
121123
//,attitudeSIN(NULL,"Device::input(matrixRot)::attitudeIN")
122124
,attitudeSIN(NULL,"Device::input(vector3)::attitudeIN")
@@ -142,7 +144,8 @@ Device( const std::string& n )
142144
forcesSOUT[3] =
143145
new Signal<Vector, int>("OpenHRP::output(vector6)::forceLARM");
144146

145-
signalRegistration( controlSIN<<stateSOUT<<velocitySOUT<<attitudeSOUT
147+
signalRegistration( controlSIN<<stateSOUT<<robotState_<<robotVelocity_
148+
<<velocitySOUT<<attitudeSOUT
146149
<<attitudeSIN<<zmpSIN <<*forcesSOUT[0]<<*forcesSOUT[1]
147150
<<*forcesSOUT[2]<<*forcesSOUT[3] <<previousControlSOUT
148151
<<pseudoTorqueSOUT << motorcontrolSOUT << ZMPPreviousControllerSOUT );
@@ -273,7 +276,16 @@ setRoot( const MatrixHomogeneous & worldMwaist )
273276
void Device::
274277
setSecondOrderIntegration()
275278
{
276-
controlInputType_ = CONTROL_INPUT_ACCELERATION;
279+
controlInputType_ = CONTROL_INPUT_TWO_INTEGRATION;
280+
velocity_.resize(state_.size());
281+
velocity_.setZero();
282+
velocitySOUT.setConstant( velocity_ );
283+
}
284+
285+
void Device::
286+
setNoIntegration()
287+
{
288+
controlInputType_ = CONTROL_INPUT_NO_INTEGRATION;
277289
velocity_.resize(state_.size());
278290
velocity_.setZero();
279291
velocitySOUT.setConstant( velocity_ );
@@ -335,12 +347,12 @@ increment( const double & dt )
335347
/* Position the signals corresponding to sensors. */
336348
stateSOUT .setConstant( state_ ); stateSOUT.setTime( time+1 );
337349
//computation of the velocity signal
338-
if( controlInputType_==CONTROL_INPUT_ACCELERATION )
350+
if( controlInputType_==CONTROL_INPUT_TWO_INTEGRATION )
339351
{
340352
velocitySOUT.setConstant( velocity_ );
341353
velocitySOUT.setTime( time+1 );
342354
}
343-
else
355+
else if (controlInputType_==CONTROL_INPUT_ONE_INTEGRATION)
344356
{
345357
velocitySOUT.setConstant( controlSIN.accessCopy() );
346358
velocitySOUT.setTime( time+1 );
@@ -383,19 +395,19 @@ increment( const double & dt )
383395

384396
void Device::integrate( const double & dt )
385397
{
386-
const Vector & control = controlSIN.accessCopy();
398+
const Vector & controlIN = controlSIN.accessCopy();
387399

388-
if (controlInputType_==CONTROL_INPUT_POSITION)
400+
if (controlInputType_==CONTROL_INPUT_NO_INTEGRATION)
389401
{
390-
assert(state_.size()==control.size()+6);
391-
for( int i=0;i<control.size();++i )
392-
state_(i+6) = control(i);
402+
assert(state_.size()==controlIN.size()+6);
403+
for( int i=0;i<controlIN.size();++i )
404+
state_(i+6) = controlIN(i);
393405
return;
394406
}
395407

396408
if( !vel_controlInit_ )
397409
{
398-
vel_control_ = Vector(control.size());
410+
vel_control_ = Vector(controlIN.size());
399411
vel_control_.setZero();
400412
vel_controlInit_ = true;
401413
}
@@ -405,20 +417,18 @@ void Device::integrate( const double & dt )
405417
// freedom as a translation and roll pitch yaw.
406418
unsigned int offset = 6;
407419

408-
409-
410-
if (controlInputType_==CONTROL_INPUT_ACCELERATION)
420+
if (controlInputType_==CONTROL_INPUT_TWO_INTEGRATION)
411421
{
412-
for( int i=0;i<control.size();++i )
422+
for( int i=0;i<controlIN.size();++i )
413423
{
414-
if(control.size() == velocity_.size()) offset = 0;
415-
vel_control_(i) = velocity_(i+offset) + control(i)*dt*0.5;
416-
velocity_(i+offset) = velocity_(i+offset) + control(i)*dt;
424+
if(controlIN.size() == velocity_.size()) offset = 0;
425+
vel_control_(i) = velocity_(i+offset) + controlIN(i)*dt*0.5;
426+
velocity_(i+offset) = velocity_(i+offset) + controlIN(i)*dt;
417427
}
418428
}
419429
else
420430
{
421-
vel_control_ = control;
431+
vel_control_ = controlIN;
422432
}
423433

424434
if (vel_control_.size() == state_.size()) {

0 commit comments

Comments
 (0)