Skip to content

Commit 373a871

Browse files
committed
Part2 of WIP jointToActuatorX(GeneralType, GeneralType)
1 parent 4b28310 commit 373a871

File tree

5 files changed

+47
-48
lines changed

5 files changed

+47
-48
lines changed

transmission_interface/include/transmission_interface/differential_transmission.h

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -143,7 +143,7 @@ class DifferentialTransmission : public Transmission
143143
* To call this method it is not required that all other data vectors contain valid data, and can even remain
144144
* empty.
145145
*/
146-
void actuatorToJointVelocity(const VelocityActuatorData& act_data, JointData& jnt_data);
146+
void actuatorToJoint(const VelocityActuatorData& act_data, JointData& jnt_data);
147147

148148
/**
149149
* \brief Transform \e position variables from actuator to joint space.
@@ -153,7 +153,7 @@ class DifferentialTransmission : public Transmission
153153
* To call this method it is not required that all other data vectors contain valid data, and can even remain
154154
* empty.
155155
*/
156-
void actuatorToJointPosition(const PositionActuatorData& act_data, JointData& jnt_data);
156+
void actuatorToJoint(const PositionActuatorData& act_data, JointData& jnt_data);
157157

158158
/**
159159
* \brief Transform \e effort variables from joint to actuator space.
@@ -163,7 +163,7 @@ class DifferentialTransmission : public Transmission
163163
* To call this method it is not required that all other data vectors contain valid data, and can even remain
164164
* empty.
165165
*/
166-
void jointToActuatorEffort(const JointData& jnt_data, EffortActuatorData& act_data);
166+
void jointToActuator(const EffortJointData& jnt_data, EffortActuatorData& act_data);
167167

168168
/**
169169
* \brief Transform \e velocity variables from joint to actuator space.
@@ -173,7 +173,7 @@ class DifferentialTransmission : public Transmission
173173
* To call this method it is not required that all other data vectors contain valid data, and can even remain
174174
* empty.
175175
*/
176-
void jointToActuatorVelocity(const JointData& jnt_data, VelocityActuatorData& act_data);
176+
void jointToActuator(const VelocityJointData& jnt_data, VelocityActuatorData& act_data);
177177

178178
/**
179179
* \brief Transform \e position variables from joint to actuator space.
@@ -183,7 +183,7 @@ class DifferentialTransmission : public Transmission
183183
* To call this method it is not required that all other data vectors contain valid data, and can even remain
184184
* empty.
185185
*/
186-
void jointToActuatorPosition(const JointData& jnt_data, PositionActuatorData& act_data);
186+
void jointToActuator(const PositionJointData& jnt_data, PositionActuatorData& act_data);
187187

188188
std::size_t numActuators() const
189189
{
@@ -243,7 +243,7 @@ inline void DifferentialTransmission::actuatorToJoint(const EffortActuatorData&
243243
*jnt_data.effort[1] = jr[1] * (*act_data.effort[0] * ar[0] - *act_data.effort[1] * ar[1]);
244244
}
245245

246-
inline void DifferentialTransmission::actuatorToJointVelocity(const VelocityActuatorData& act_data, JointData& jnt_data)
246+
inline void DifferentialTransmission::actuatorToJoint(const VelocityActuatorData& act_data, JointData& jnt_data)
247247
{
248248
assert(numActuators() == act_data.velocity.size() && numJoints() == jnt_data.velocity.size());
249249
assert(act_data.velocity[0] && act_data.velocity[1] && jnt_data.velocity[0] && jnt_data.velocity[1]);
@@ -255,7 +255,7 @@ inline void DifferentialTransmission::actuatorToJointVelocity(const VelocityActu
255255
*jnt_data.velocity[1] = (*act_data.velocity[0] / ar[0] - *act_data.velocity[1] / ar[1]) / (2.0 * jr[1]);
256256
}
257257

258-
inline void DifferentialTransmission::actuatorToJointPosition(const PositionActuatorData& act_data, JointData& jnt_data)
258+
inline void DifferentialTransmission::actuatorToJoint(const PositionActuatorData& act_data, JointData& jnt_data)
259259
{
260260
assert(numActuators() == act_data.position.size() && numJoints() == jnt_data.position.size());
261261
assert(act_data.position[0] && act_data.position[1] && jnt_data.position[0] && jnt_data.position[1]);
@@ -269,7 +269,7 @@ inline void DifferentialTransmission::actuatorToJointPosition(const PositionActu
269269
(*act_data.position[0] / ar[0] - *act_data.position[1] / ar[1]) / (2.0 * jr[1]) + jnt_offset_[1];
270270
}
271271

272-
inline void DifferentialTransmission::jointToActuatorEffort(const JointData& jnt_data, EffortActuatorData& act_data)
272+
inline void DifferentialTransmission::jointToActuator(const EffortJointData& jnt_data, EffortActuatorData& act_data)
273273
{
274274
assert(numActuators() == act_data.effort.size() && numJoints() == jnt_data.effort.size());
275275
assert(act_data.effort[0] && act_data.effort[1] && jnt_data.effort[0] && jnt_data.effort[1]);
@@ -281,7 +281,7 @@ inline void DifferentialTransmission::jointToActuatorEffort(const JointData& jnt
281281
*act_data.effort[1] = (*jnt_data.effort[0] / jr[0] - *jnt_data.effort[1] / jr[1]) / (2.0 * ar[1]);
282282
}
283283

284-
inline void DifferentialTransmission::jointToActuatorVelocity(const JointData& jnt_data, VelocityActuatorData& act_data)
284+
inline void DifferentialTransmission::jointToActuator(const VelocityJointData& jnt_data, VelocityActuatorData& act_data)
285285
{
286286
assert(numActuators() == act_data.velocity.size() && numJoints() == jnt_data.velocity.size());
287287
assert(act_data.velocity[0] && act_data.velocity[1] && jnt_data.velocity[0] && jnt_data.velocity[1]);
@@ -293,7 +293,7 @@ inline void DifferentialTransmission::jointToActuatorVelocity(const JointData& j
293293
*act_data.velocity[1] = (*jnt_data.velocity[0] * jr[0] - *jnt_data.velocity[1] * jr[1]) * ar[1];
294294
}
295295

296-
inline void DifferentialTransmission::jointToActuatorPosition(const JointData& jnt_data, PositionActuatorData& act_data)
296+
inline void DifferentialTransmission::jointToActuator(const PositionJointData& jnt_data, PositionActuatorData& act_data)
297297
{
298298
assert(numActuators() == act_data.position.size() && numJoints() == jnt_data.position.size());
299299
assert(act_data.position[0] && act_data.position[1] && jnt_data.position[0] && jnt_data.position[1]);

transmission_interface/include/transmission_interface/four_bar_linkage_transmission.h

Lines changed: 10 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -144,7 +144,7 @@ class FourBarLinkageTransmission : public Transmission
144144
* To call this method it is not required that all other data vectors contain valid data, and can even remain
145145
* empty.
146146
*/
147-
void actuatorToJointVelocity(const VelocityActuatorData& act_data, JointData& jnt_data);
147+
void actuatorToJoint(const VelocityActuatorData& act_data, JointData& jnt_data);
148148

149149
/**
150150
* \brief Transform \e position variables from actuator to joint space.
@@ -154,7 +154,7 @@ class FourBarLinkageTransmission : public Transmission
154154
* To call this method it is not required that all other data vectors contain valid data, and can even remain
155155
* empty.
156156
*/
157-
void actuatorToJointPosition(const PositionActuatorData& act_data, JointData& jnt_data);
157+
void actuatorToJoint(const PositionActuatorData& act_data, JointData& jnt_data);
158158

159159
/**
160160
* \brief Transform \e effort variables from joint to actuator space.
@@ -164,7 +164,7 @@ class FourBarLinkageTransmission : public Transmission
164164
* To call this method it is not required that all other data vectors contain valid data, and can even remain
165165
* empty.
166166
*/
167-
void jointToActuatorEffort(const JointData& jnt_data, EffortActuatorData& act_data);
167+
void jointToActuator(const EffortJointData& jnt_data, EffortActuatorData& act_data);
168168

169169
/**
170170
* \brief Transform \e velocity variables from joint to actuator space.
@@ -174,7 +174,7 @@ class FourBarLinkageTransmission : public Transmission
174174
* To call this method it is not required that all other data vectors contain valid data, and can even remain
175175
* empty.
176176
*/
177-
void jointToActuatorVelocity(const JointData& jnt_data, VelocityActuatorData& act_data);
177+
void jointToActuator(const VelocityJointData& jnt_data, VelocityActuatorData& act_data);
178178

179179
/**
180180
* \brief Transform \e position variables from joint to actuator space.
@@ -184,7 +184,7 @@ class FourBarLinkageTransmission : public Transmission
184184
* To call this method it is not required that all other data vectors contain valid data, and can even remain
185185
* empty.
186186
*/
187-
void jointToActuatorPosition(const JointData& jnt_data, PositionActuatorData& act_data);
187+
void jointToActuator(const PositionJointData& jnt_data, PositionActuatorData& act_data);
188188

189189
std::size_t numActuators() const
190190
{
@@ -243,8 +243,7 @@ inline void FourBarLinkageTransmission::actuatorToJoint(const EffortActuatorData
243243
*jnt_data.effort[1] = jr[1] * (*act_data.effort[1] * ar[1] - *act_data.effort[0] * ar[0] * jr[0]);
244244
}
245245

246-
inline void FourBarLinkageTransmission::actuatorToJointVelocity(const VelocityActuatorData& act_data,
247-
JointData& jnt_data)
246+
inline void FourBarLinkageTransmission::actuatorToJoint(const VelocityActuatorData& act_data, JointData& jnt_data)
248247
{
249248
assert(numActuators() == act_data.velocity.size() && numJoints() == jnt_data.velocity.size());
250249
assert(act_data.velocity[0] && act_data.velocity[1] && jnt_data.velocity[0] && jnt_data.velocity[1]);
@@ -256,7 +255,7 @@ inline void FourBarLinkageTransmission::actuatorToJointVelocity(const VelocityAc
256255
*jnt_data.velocity[1] = (*act_data.velocity[1] / ar[1] - *act_data.velocity[0] / (jr[0] * ar[0])) / jr[1];
257256
}
258257

259-
inline void FourBarLinkageTransmission::actuatorToJointPosition(const PositionActuatorData& act_data,
258+
inline void FourBarLinkageTransmission::actuatorToJoint(const PositionActuatorData& act_data,
260259
JointData& jnt_data)
261260
{
262261
assert(numActuators() == act_data.position.size() && numJoints() == jnt_data.position.size());
@@ -270,7 +269,7 @@ inline void FourBarLinkageTransmission::actuatorToJointPosition(const PositionAc
270269
(*act_data.position[1] / ar[1] - *act_data.position[0] / (jr[0] * ar[0])) / jr[1] + jnt_offset_[1];
271270
}
272271

273-
inline void FourBarLinkageTransmission::jointToActuatorEffort(const JointData& jnt_data, EffortActuatorData& act_data)
272+
inline void FourBarLinkageTransmission::jointToActuator(const EffortJointData& jnt_data, EffortActuatorData& act_data)
274273
{
275274
assert(numActuators() == act_data.effort.size() && numJoints() == jnt_data.effort.size());
276275
assert(act_data.effort[0] && act_data.effort[1] && jnt_data.effort[0] && jnt_data.effort[1]);
@@ -282,7 +281,7 @@ inline void FourBarLinkageTransmission::jointToActuatorEffort(const JointData& j
282281
*act_data.effort[1] = (*jnt_data.effort[0] + *jnt_data.effort[1] / jr[1]) / ar[1];
283282
}
284283

285-
inline void FourBarLinkageTransmission::jointToActuatorVelocity(const JointData& jnt_data,
284+
inline void FourBarLinkageTransmission::jointToActuator(const VelocityJointData& jnt_data,
286285
VelocityActuatorData& act_data)
287286
{
288287
assert(numActuators() == act_data.velocity.size() && numJoints() == jnt_data.velocity.size());
@@ -295,7 +294,7 @@ inline void FourBarLinkageTransmission::jointToActuatorVelocity(const JointData&
295294
*act_data.velocity[1] = (*jnt_data.velocity[0] + *jnt_data.velocity[1] * jr[1]) * ar[1];
296295
}
297296

298-
inline void FourBarLinkageTransmission::jointToActuatorPosition(const JointData& jnt_data,
297+
inline void FourBarLinkageTransmission::jointToActuator(const PositionJointData& jnt_data,
299298
PositionActuatorData& act_data)
300299
{
301300
assert(numActuators() == act_data.position.size() && numJoints() == jnt_data.position.size());

transmission_interface/include/transmission_interface/simple_transmission.h

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -119,7 +119,7 @@ class SimpleTransmission : public Transmission
119119
* To call this method it is not required that all other data vectors contain valid data, and can even remain
120120
* empty.
121121
*/
122-
void actuatorToJointVelocity(const VelocityActuatorData& act_data, JointData& jnt_data);
122+
void actuatorToJoint(const VelocityActuatorData& act_data, JointData& jnt_data);
123123

124124
/**
125125
* \brief Transform \e position variables from actuator to joint space.
@@ -129,7 +129,7 @@ class SimpleTransmission : public Transmission
129129
* To call this method it is not required that all other data vectors contain valid data, and can even remain
130130
* empty.
131131
*/
132-
void actuatorToJointPosition(const PositionActuatorData& act_data, JointData& jnt_data);
132+
void actuatorToJoint(const PositionActuatorData& act_data, JointData& jnt_data);
133133

134134
/**
135135
* \brief Transform \e effort variables from joint to actuator space.
@@ -139,7 +139,7 @@ class SimpleTransmission : public Transmission
139139
* To call this method it is not required that all other data vectors contain valid data, and can even remain
140140
* empty.
141141
*/
142-
void jointToActuatorEffort(const JointData& jnt_data, EffortActuatorData& act_data);
142+
void jointToActuator(const EffortJointData& jnt_data, EffortActuatorData& act_data);
143143

144144
/**
145145
* \brief Transform \e velocity variables from joint to actuator space.
@@ -149,7 +149,7 @@ class SimpleTransmission : public Transmission
149149
* To call this method it is not required that all other data vectors contain valid data, and can even remain
150150
* empty.
151151
*/
152-
void jointToActuatorVelocity(const JointData& jnt_data, VelocityActuatorData& act_data);
152+
void jointToActuator(const VelocityJointData& jnt_data, VelocityActuatorData& act_data);
153153

154154
/**
155155
* \brief Transform \e position variables from joint to actuator space.
@@ -159,7 +159,7 @@ class SimpleTransmission : public Transmission
159159
* To call this method it is not required that all other data vectors contain valid data, and can even remain
160160
* empty.
161161
*/
162-
void jointToActuatorPosition(const JointData& jnt_data, PositionActuatorData& act_data);
162+
void jointToActuator(const PositionJointData& jnt_data, PositionActuatorData& act_data);
163163

164164
std::size_t numActuators() const
165165
{
@@ -201,39 +201,39 @@ inline void SimpleTransmission::actuatorToJoint(const EffortActuatorData& act_da
201201
*jnt_data.effort[0] = *act_data.effort[0] * reduction_;
202202
}
203203

204-
inline void SimpleTransmission::actuatorToJointVelocity(const VelocityActuatorData& act_data, JointData& jnt_data)
204+
inline void SimpleTransmission::actuatorToJoint(const VelocityActuatorData& act_data, JointData& jnt_data)
205205
{
206206
assert(numActuators() == act_data.velocity.size() && numJoints() == jnt_data.velocity.size());
207207
assert(act_data.velocity[0] && jnt_data.velocity[0]);
208208

209209
*jnt_data.velocity[0] = *act_data.velocity[0] / reduction_;
210210
}
211211

212-
inline void SimpleTransmission::actuatorToJointPosition(const PositionActuatorData& act_data, JointData& jnt_data)
212+
inline void SimpleTransmission::actuatorToJoint(const PositionActuatorData& act_data, JointData& jnt_data)
213213
{
214214
assert(numActuators() == act_data.position.size() && numJoints() == jnt_data.position.size());
215215
assert(act_data.position[0] && jnt_data.position[0]);
216216

217217
*jnt_data.position[0] = *act_data.position[0] / reduction_ + jnt_offset_;
218218
}
219219

220-
inline void SimpleTransmission::jointToActuatorEffort(const JointData& jnt_data, EffortActuatorData& act_data)
220+
inline void SimpleTransmission::jointToActuator(const EffortJointData& jnt_data, EffortActuatorData& act_data)
221221
{
222222
assert(numActuators() == act_data.effort.size() && numJoints() == jnt_data.effort.size());
223223
assert(act_data.effort[0] && jnt_data.effort[0]);
224224

225225
*act_data.effort[0] = *jnt_data.effort[0] / reduction_;
226226
}
227227

228-
inline void SimpleTransmission::jointToActuatorVelocity(const JointData& jnt_data, VelocityActuatorData& act_data)
228+
inline void SimpleTransmission::jointToActuator(const VelocityJointData& jnt_data, VelocityActuatorData& act_data)
229229
{
230230
assert(numActuators() == act_data.velocity.size() && numJoints() == jnt_data.velocity.size());
231231
assert(act_data.velocity[0] && jnt_data.velocity[0]);
232232

233233
*act_data.velocity[0] = *jnt_data.velocity[0] * reduction_;
234234
}
235235

236-
inline void SimpleTransmission::jointToActuatorPosition(const JointData& jnt_data, PositionActuatorData& act_data)
236+
inline void SimpleTransmission::jointToActuator(const PositionJointData& jnt_data, PositionActuatorData& act_data)
237237
{
238238
assert(numActuators() == act_data.position.size() && numJoints() == jnt_data.position.size());
239239
assert(act_data.position[0] && jnt_data.position[0]);

transmission_interface/include/transmission_interface/transmission.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,7 @@ class Transmission
8787
* transmission actuators and joints.
8888
* Data vectors not used in this map can remain empty.
8989
*/
90-
virtual void actuatorToJointVelocity(const VelocityActuatorData& act_data, JointData& jnt_data) = 0;
90+
virtual void actuatorToJoint(const VelocityActuatorData& act_data, JointData& jnt_data) = 0;
9191

9292
/**
9393
* \brief Transform \e position variables from actuator to joint space.
@@ -97,7 +97,7 @@ class Transmission
9797
* transmission actuators and joints.
9898
* Data vectors not used in this map can remain empty.
9999
*/
100-
virtual void actuatorToJointPosition(const PositionActuatorData& act_data, JointData& jnt_data) = 0;
100+
virtual void actuatorToJoint(const PositionActuatorData& act_data, JointData& jnt_data) = 0;
101101

102102
/**
103103
* \brief Transform \e effort variables from joint to actuator space.
@@ -107,7 +107,7 @@ class Transmission
107107
* transmission actuators and joints.
108108
* Data vectors not used in this map can remain empty.
109109
*/
110-
virtual void jointToActuatorEffort(const JointData& jnt_data, EffortActuatorData& act_data) = 0;
110+
virtual void jointToActuator(const EffortJointData& jnt_data, EffortActuatorData& act_data) = 0;
111111

112112
/**
113113
* \brief Transform \e velocity variables from joint to actuator space.
@@ -117,7 +117,7 @@ class Transmission
117117
* transmission actuators and joints.
118118
* Data vectors not used in this map can remain empty.
119119
*/
120-
virtual void jointToActuatorVelocity(const JointData& jnt_data, VelocityActuatorData& act_data) = 0;
120+
virtual void jointToActuator(const VelocityJointData& jnt_data, VelocityActuatorData& act_data) = 0;
121121

122122
/**
123123
* \brief Transform \e position variables from joint to actuator space.
@@ -127,7 +127,7 @@ class Transmission
127127
* transmission actuators and joints.
128128
* Data vectors not used in this map can remain empty.
129129
*/
130-
virtual void jointToActuatorPosition(const JointData& jnt_data, PositionActuatorData& act_data) = 0;
130+
virtual void jointToActuator(const PositionJointData& jnt_data, PositionActuatorData& act_data) = 0;
131131

132132
/** \return Number of actuators managed by transmission, ie. the dimension of the actuator space. */
133133
virtual std::size_t numActuators() const = 0;

0 commit comments

Comments
 (0)