Skip to content

Commit

Permalink
Add new parameter methods to ICartesianControl, prepare stub impl (#121)
Browse files Browse the repository at this point in the history
  • Loading branch information
PeterBowman committed Jan 19, 2018
1 parent cdc0133 commit 704de8a
Show file tree
Hide file tree
Showing 7 changed files with 157 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,14 @@ class AmorCartesianControl : public yarp::dev::DeviceDriver, public ICartesianCo

virtual void pose(const std::vector<double> &x, double interval);

virtual bool setParameter(int vocab, const std::string & value);

virtual bool getParameter(int vocab, std::string & value);

virtual bool setParameter(int vocab, double value);

virtual bool setParameter(int vocab, double * value);

// -------- DeviceDriver declarations. Implementation in DeviceDriverImpl.cpp --------

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -575,3 +575,31 @@ void roboticslab::AmorCartesianControl::pose(const std::vector<double> &x, doubl
}

// -----------------------------------------------------------------------------

bool roboticslab::AmorCartesianControl::setParameter(int vocab, const std::string & value)
{
return true;
}

// -----------------------------------------------------------------------------

bool roboticslab::AmorCartesianControl::getParameter(int vocab, std::string & value)
{
return true;
}

// -----------------------------------------------------------------------------

bool roboticslab::AmorCartesianControl::setParameter(int vocab, double value)
{
return true;
}

// -----------------------------------------------------------------------------

bool roboticslab::AmorCartesianControl::setParameter(int vocab, double * value)
{
return true;
}

// -----------------------------------------------------------------------------
Original file line number Diff line number Diff line change
Expand Up @@ -150,6 +150,14 @@ class BasicCartesianControl : public yarp::dev::DeviceDriver, public ICartesianC

virtual void pose(const std::vector<double> &x, double interval);

virtual bool setParameter(int vocab, const std::string & value);

virtual bool getParameter(int vocab, std::string & value);

virtual bool setParameter(int vocab, double value);

virtual bool setParameter(int vocab, double * value);

// -------- RateThread declarations. Implementation in RateThreadImpl.cpp --------

/** Loop function. This is the thread itself. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -586,3 +586,31 @@ void roboticslab::BasicCartesianControl::pose(const std::vector<double> &x, doub
}

// -----------------------------------------------------------------------------

bool roboticslab::BasicCartesianControl::setParameter(int vocab, const std::string & value)
{
return true;
}

// -----------------------------------------------------------------------------

bool roboticslab::BasicCartesianControl::getParameter(int vocab, std::string & value)
{
return true;
}

// -----------------------------------------------------------------------------

bool roboticslab::BasicCartesianControl::setParameter(int vocab, double value)
{
return true;
}

// -----------------------------------------------------------------------------

bool roboticslab::BasicCartesianControl::setParameter(int vocab, double * value)
{
return true;
}

// -----------------------------------------------------------------------------
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,14 @@ class CartesianControlClient : public yarp::dev::DeviceDriver, public ICartesian

virtual void pose(const std::vector<double> &x, double interval);

virtual bool setParameter(int vocab, const std::string & value);

virtual bool getParameter(int vocab, std::string & value);

virtual bool setParameter(int vocab, double value);

virtual bool setParameter(int vocab, double * value);

// -------- DeviceDriver declarations. Implementation in IDeviceImpl.cpp --------

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -261,3 +261,31 @@ void roboticslab::CartesianControlClient::pose(const std::vector<double> &x, dou
}

// -----------------------------------------------------------------------------

bool roboticslab::CartesianControlClient::setParameter(int vocab, const std::string & value)
{
return true;
}

// -----------------------------------------------------------------------------

bool roboticslab::CartesianControlClient::getParameter(int vocab, std::string & value)
{
return true;
}

// -----------------------------------------------------------------------------

bool roboticslab::CartesianControlClient::setParameter(int vocab, double value)
{
return true;
}

// -----------------------------------------------------------------------------

bool roboticslab::CartesianControlClient::setParameter(int vocab, double * value)
{
return true;
}

// -----------------------------------------------------------------------------
49 changes: 49 additions & 0 deletions libraries/YarpPlugins/ICartesianControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#ifndef __I_CARTESIAN_CONTROL__
#define __I_CARTESIAN_CONTROL__

#include <string>
#include <vector>

#include <yarp/os/Vocab.h>
Expand Down Expand Up @@ -342,6 +343,54 @@ class ICartesianControl
*/
virtual void pose(const std::vector<double> &x, double interval) = 0;

/**
* @brief Set a configuration parameter.
*
* Ask the controller to store or update a parameter of type std::string.
*
* @param vocab YARP-encoded vocab (parameter key).
* @param value Parameter value encoded as a string.
*
* @return true on success, false otherwise
*/
virtual bool setParameter(int vocab, const std::string & value) = 0;

/**
* @brief Retrieve a configuration parameter.
*
* Ask the controller to retrieve a parameter of type std::string.
*
* @param vocab YARP-encoded vocab (parameter key).
* @param value Parameter value encoded as a string.
*
* @return true on success, false otherwise
*/
virtual bool getParameter(int vocab, std::string & value) = 0;

/**
* @brief Set a configuration parameter.
*
* Ask the controller to store or update a parameter of type double.
*
* @param vocab YARP-encoded vocab (parameter key).
* @param value Parameter value encoded as a double.
*
* @return true on success, false otherwise
*/
virtual bool setParameter(int vocab, double value) = 0;

/**
* @brief Retrieve a configuration parameter.
*
* Ask the controller to retrieve a parameter of type double.
*
* @param vocab YARP-encoded vocab (parameter key).
* @param value Parameter value encoded as a double.
*
* @return true on success, false otherwise
*/
virtual bool setParameter(int vocab, double * value) = 0;

/** @} */
};

Expand Down

0 comments on commit 704de8a

Please sign in to comment.