Skip to content

Commit

Permalink
Merge branch 'cc-wait-period' into develop
Browse files Browse the repository at this point in the history
  • Loading branch information
PeterBowman committed Feb 3, 2018
2 parents 816f64d + 0d7375a commit 1f62c00
Show file tree
Hide file tree
Showing 8 changed files with 37 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#define DEFAULT_GAIN 0.05
#define DEFAULT_QDOT_LIMIT 10.0
#define DEFAULT_WAIT_PERIOD_MS 30
#define DEFAULT_REFERENCE_FRAME "base"

namespace roboticslab
Expand Down Expand Up @@ -45,6 +46,7 @@ class AmorCartesianControl : public yarp::dev::DeviceDriver, public ICartesianCo
currentState(VOCAB_CC_NOT_CONTROLLING),
gain(DEFAULT_GAIN),
maxJointVelocity(DEFAULT_QDOT_LIMIT),
waitPeriodMs(DEFAULT_WAIT_PERIOD_MS),
referenceFrame(BASE_FRAME)
{}

Expand Down Expand Up @@ -125,6 +127,7 @@ class AmorCartesianControl : public yarp::dev::DeviceDriver, public ICartesianCo

double gain;
double maxJointVelocity;
int waitPeriodMs;

reference_frame referenceFrame;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,9 @@ bool roboticslab::AmorCartesianControl::open(yarp::os::Searchable& config)
maxJointVelocity = config.check("maxJointVelocity", yarp::os::Value(DEFAULT_QDOT_LIMIT),
"maximum joint velocity").asDouble();

waitPeriodMs = config.check("waitPeriodMs", yarp::os::Value(DEFAULT_WAIT_PERIOD_MS),
"wait period [ms]").asInt();

std::string referenceFrameStr = config.check("referenceFrame", yarp::os::Value(DEFAULT_REFERENCE_FRAME),
"reference frame").asString();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -277,7 +277,7 @@ bool roboticslab::AmorCartesianControl::wait(double timeout)
break;
}

yarp::os::Time::delay(0.5); // seconds
yarp::os::Time::delay(waitPeriodMs / 1000.0);
}
while (status != AMOR_MOVEMENT_STATUS_FINISHED);

Expand Down Expand Up @@ -424,6 +424,14 @@ bool roboticslab::AmorCartesianControl::setParameter(int vocab, double value)
}
maxJointVelocity = value;
break;
case VOCAB_CC_CONFIG_WAIT_PERIOD:
if (value <= 0.0)
{
CD_ERROR("Wait period cannot be negative nor zero.\n");
return false;
}
waitPeriodMs = value;
break;
case VOCAB_CC_CONFIG_FRAME:
if (value != BASE_FRAME && value != TCP_FRAME)
{
Expand Down Expand Up @@ -452,6 +460,9 @@ bool roboticslab::AmorCartesianControl::getParameter(int vocab, double * value)
case VOCAB_CC_CONFIG_MAX_JOINT_VEL:
*value = maxJointVelocity;
break;
case VOCAB_CC_CONFIG_WAIT_PERIOD:
*value = waitPeriodMs;
break;
case VOCAB_CC_CONFIG_FRAME:
*value = referenceFrame;
break;
Expand Down Expand Up @@ -483,6 +494,7 @@ bool roboticslab::AmorCartesianControl::getParameters(std::map<int, double> & pa
{
params.insert(std::pair<int, double>(VOCAB_CC_CONFIG_GAIN, gain));
params.insert(std::pair<int, double>(VOCAB_CC_CONFIG_MAX_JOINT_VEL, maxJointVelocity));
params.insert(std::pair<int, double>(VOCAB_CC_CONFIG_WAIT_PERIOD, waitPeriodMs));
params.insert(std::pair<int, double>(VOCAB_CC_CONFIG_FRAME, referenceFrame));
return true;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#define DEFAULT_QDOT_LIMIT 10.0
#define DEFAULT_DURATION 10.0
#define DEFAULT_CMC_RATE_MS 50
#define DEFAULT_WAIT_PERIOD_MS 30
#define DEFAULT_REFERENCE_FRAME "base"

namespace roboticslab
Expand Down Expand Up @@ -208,6 +209,7 @@ class BasicCartesianControl : public yarp::dev::DeviceDriver, public ICartesianC
double maxJointVelocity;
double duration; // [s]
int cmcRateMs;
int waitPeriodMs;
int numRobotJoints, numSolverJoints;

/** State encoded as a VOCAB which can be stored as an int */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ bool roboticslab::BasicCartesianControl::open(yarp::os::Searchable& config) {
maxJointVelocity = config.check("maxJointVelocity",yarp::os::Value(DEFAULT_QDOT_LIMIT),"maximum joint velocity").asDouble();
duration = config.check("trajectoryDuration",yarp::os::Value(DEFAULT_DURATION),"trajectory duration").asDouble();
cmcRateMs = config.check("cmcRateMs",yarp::os::Value(DEFAULT_CMC_RATE_MS),"CMC rate [ms]").asInt();
waitPeriodMs = config.check("waitPeriodMs",yarp::os::Value(DEFAULT_WAIT_PERIOD_MS),"wait period [ms]").asInt();

std::string referenceFrameStr = config.check("referenceFrame", yarp::os::Value(DEFAULT_REFERENCE_FRAME),
"reference frame").asString();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -320,7 +320,7 @@ bool roboticslab::BasicCartesianControl::wait(double timeout)
break;
}

yarp::os::Time::delay(0.5);
yarp::os::Time::delay(waitPeriodMs / 1000.0);
state = getCurrentState();
}

Expand Down Expand Up @@ -476,6 +476,14 @@ bool roboticslab::BasicCartesianControl::setParameter(int vocab, double value)
}
cmcRateMs = value;
break;
case VOCAB_CC_CONFIG_WAIT_PERIOD:
if (value <= 0.0)
{
CD_ERROR("Wait period cannot be negative nor zero.\n");
return false;
}
waitPeriodMs = value;
break;
case VOCAB_CC_CONFIG_FRAME:
if (value != BASE_FRAME && value != TCP_FRAME)
{
Expand Down Expand Up @@ -510,6 +518,9 @@ bool roboticslab::BasicCartesianControl::getParameter(int vocab, double * value)
case VOCAB_CC_CONFIG_CMC_RATE:
*value = cmcRateMs;
break;
case VOCAB_CC_CONFIG_WAIT_PERIOD:
*value = waitPeriodMs;
break;
case VOCAB_CC_CONFIG_FRAME:
*value = referenceFrame;
break;
Expand Down Expand Up @@ -543,6 +554,7 @@ bool roboticslab::BasicCartesianControl::getParameters(std::map<int, double> & p
params.insert(std::pair<int, double>(VOCAB_CC_CONFIG_MAX_JOINT_VEL, maxJointVelocity));
params.insert(std::pair<int, double>(VOCAB_CC_CONFIG_TRAJ_DURATION, duration));
params.insert(std::pair<int, double>(VOCAB_CC_CONFIG_CMC_RATE, cmcRateMs));
params.insert(std::pair<int, double>(VOCAB_CC_CONFIG_WAIT_PERIOD, waitPeriodMs));
params.insert(std::pair<int, double>(VOCAB_CC_CONFIG_FRAME, referenceFrame));
return true;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,7 @@ void roboticslab::RpcResponder::makeUsage()
addUsage("... [cpjv] value", "(config param) maximum joint velocity");
addUsage("... [cptd] value", "(config param) trajectory duration");
addUsage("... [cpcr] value", "(config param) CMC rate [ms]");
addUsage("... [cpwp] value", "(config param) check period of 'wait' command [ms]");
addUsage("... [cpf] [cpfb]", "(config param) reference frame (base)");
addUsage("... [cpf] [cpft]", "(config param) reference frame (TCP)");
}
Expand Down
1 change: 1 addition & 0 deletions libraries/YarpPlugins/ICartesianControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -105,6 +105,7 @@
#define VOCAB_CC_CONFIG_MAX_JOINT_VEL VOCAB4('c','p','j','v') ///< Maximum joint velocity
#define VOCAB_CC_CONFIG_TRAJ_DURATION VOCAB4('c','p','t','d') ///< Trajectory duration
#define VOCAB_CC_CONFIG_CMC_RATE VOCAB4('c','p','c','r') ///< CMC rate [ms]
#define VOCAB_CC_CONFIG_WAIT_PERIOD VOCAB4('c','p','w','p') ///< Check period of 'wait' command [ms]
#define VOCAB_CC_CONFIG_FRAME VOCAB3('c','p','f') ///< Reference frame

/** @} */
Expand Down

0 comments on commit 1f62c00

Please sign in to comment.