Skip to content

Commit c187abd

Browse files
committed
Use actual vocab values in makeUsage()
1 parent e76d3bf commit c187abd

File tree

1 file changed

+93
-22
lines changed

1 file changed

+93
-22
lines changed

libraries/YarpPlugins/CartesianControlServer/RpcResponder.cpp

+93-22
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,10 @@
22

33
#include "CartesianControlServer.hpp"
44

5+
#include <sstream>
6+
7+
#include <yarp/os/Vocab.h>
8+
59
#include <ColorDebug.h>
610

711
// -----------------------------------------------------------------------------
@@ -82,28 +86,95 @@ bool roboticslab::RpcResponder::respond(const yarp::os::Bottle& in, yarp::os::Bo
8286

8387
void roboticslab::RpcResponder::makeUsage()
8488
{
85-
addUsage("[stat]", "get current position in cartesian space");
86-
addUsage("[inv] coord1 coord2 ...", "accept desired position in cartesian space, return result in joint space");
87-
addUsage("[movj] coord1 coord2 ...", "joint move to desired position (absolute coordinates in cartesian space)");
88-
addUsage("[relj] coord1 coord2 ...", "joint move to desired position (relative coordinates in cartesian space)");
89-
addUsage("[movl] coord1 coord2 ...", "linear move to desired position (absolute coordinates in cartesian space)");
90-
addUsage("[movv] coord1 coord2 ...", "velocity move using supplied vector (cartesian space)");
91-
addUsage("[gcmp]", "enable gravity compensation");
92-
addUsage("[forc] coord1 coord2 ...", "enable torque control, apply input forces (cartesian space)");
93-
addUsage("[stop]", "stop control");
94-
addUsage("[wait] timeout", "wait until completion with timeout (optional, 0.0 means no timeout)");
95-
addUsage("[tool] coord1 coord2 ...", "append fixed link to end effector");
96-
addUsage("[set] vocab value", "set configuration parameter");
97-
addUsage("[get] vocab", "get configuration parameter");
98-
addUsage("[set] [prms] (vocab value) ...", "set multiple configuration parameters");
99-
addUsage("[get] [prms]", "get all configuration parameters");
100-
addUsage("... [cpcg] value", "(config param) controller gain");
101-
addUsage("... [cpjv] value", "(config param) maximum joint velocity");
102-
addUsage("... [cptd] value", "(config param) trajectory duration");
103-
addUsage("... [cpcr] value", "(config param) CMC rate [ms]");
104-
addUsage("... [cpwp] value", "(config param) check period of 'wait' command [ms]");
105-
addUsage("... [cpf] [cpfb]", "(config param) reference frame (base)");
106-
addUsage("... [cpf] [cpft]", "(config param) reference frame (TCP)");
89+
std::stringstream ss;
90+
91+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_STAT) << "]";
92+
addUsage(ss.str().c_str(), "get current position in cartesian space");
93+
ss.str("");
94+
95+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_INV) << "] coord1 coord2 ...";
96+
addUsage(ss.str().c_str(), "accept desired position in cartesian space, return result in joint space");
97+
ss.str("");
98+
99+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_MOVJ) << "] coord1 coord2 ...";
100+
addUsage(ss.str().c_str(), "joint move to desired position (absolute coordinates in cartesian space)");
101+
ss.str("");
102+
103+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_RELJ) << "] coord1 coord2 ...";
104+
addUsage(ss.str().c_str(), "joint move to desired position (relative coordinates in cartesian space)");
105+
ss.str("");
106+
107+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_MOVL) << "] coord1 coord2 ...";
108+
addUsage(ss.str().c_str(), "linear move to desired position (absolute coordinates in cartesian space)");
109+
ss.str("");
110+
111+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_MOVV) << "] coord1 coord2 ...";
112+
addUsage(ss.str().c_str(), "velocity move using supplied vector (cartesian space)");
113+
ss.str("");
114+
115+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_GCMP) << "]";
116+
addUsage(ss.str().c_str(), "enable gravity compensation");
117+
ss.str("");
118+
119+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_FORC) << "] coord1 coord2 ...";
120+
addUsage(ss.str().c_str(), "enable torque control, apply input forces (cartesian space)");
121+
ss.str("");
122+
123+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_STOP) << "]";
124+
addUsage(ss.str().c_str(), "stop control");
125+
ss.str("");
126+
127+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_WAIT) << "] timeout";
128+
addUsage(ss.str().c_str(), "wait until completion with timeout (optional, 0.0 means no timeout)");
129+
ss.str("");
130+
131+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_TOOL) << "] coord1 coord2 ...";
132+
addUsage(ss.str().c_str(), "append fixed link to end effector");
133+
ss.str("");
134+
135+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_SET) << "] vocab value";
136+
addUsage(ss.str().c_str(), "set configuration parameter");
137+
ss.str("");
138+
139+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_GET) << "] vocab";
140+
addUsage(ss.str().c_str(), "get configuration parameter");
141+
ss.str("");
142+
143+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_SET) << "] [" << yarp::os::Vocab::decode(VOCAB_CC_CONFIG_PARAMS) << "] (vocab value) ...";
144+
addUsage(ss.str().c_str(), "set multiple configuration parameters");
145+
ss.str("");
146+
147+
ss << "[" << yarp::os::Vocab::decode(VOCAB_CC_GET) << "] [" << yarp::os::Vocab::decode(VOCAB_CC_CONFIG_PARAMS) << "]";
148+
addUsage(ss.str().c_str(), "get all configuration parameters");
149+
ss.str("");
150+
151+
ss << "... [" << yarp::os::Vocab::decode(VOCAB_CC_CONFIG_GAIN) << "] value";
152+
addUsage(ss.str().c_str(), "(config param) controller gain");
153+
ss.str("");
154+
155+
ss << "... [" << yarp::os::Vocab::decode(VOCAB_CC_CONFIG_MAX_JOINT_VEL) << "] value";
156+
addUsage(ss.str().c_str(), "(config param) maximum joint velocity");
157+
ss.str("");
158+
159+
ss << "... [" << yarp::os::Vocab::decode(VOCAB_CC_CONFIG_TRAJ_DURATION) << "] value";
160+
addUsage(ss.str().c_str(), "(config param) trajectory duration");
161+
ss.str("");
162+
163+
ss << "... [" << yarp::os::Vocab::decode(VOCAB_CC_CONFIG_CMC_RATE) << "] value";
164+
addUsage(ss.str().c_str(), "(config param) CMC rate [ms]");
165+
ss.str("");
166+
167+
ss << "... [" << yarp::os::Vocab::decode(VOCAB_CC_CONFIG_WAIT_PERIOD) << "] value";
168+
addUsage(ss.str().c_str(), "(config param) check period of 'wait' command [ms]");
169+
ss.str("");
170+
171+
ss << "... [" << yarp::os::Vocab::decode(VOCAB_CC_CONFIG_FRAME) << "] [" << yarp::os::Vocab::decode(ICartesianSolver::BASE_FRAME) << "]";
172+
addUsage(ss.str().c_str(), "(config param) reference frame (base)");
173+
ss.str("");
174+
175+
ss << "... [" << yarp::os::Vocab::decode(VOCAB_CC_CONFIG_FRAME) << "] [" << yarp::os::Vocab::decode(ICartesianSolver::TCP_FRAME) << "]";
176+
addUsage(ss.str().c_str(), "(config param) reference frame (TCP)");
177+
ss.str("");
107178
}
108179

109180
// -----------------------------------------------------------------------------

0 commit comments

Comments
 (0)