Skip to content

Commit 5cabd14

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

File tree

5 files changed

+9
-10
lines changed

5 files changed

+9
-10
lines changed

transmission_interface/include/transmission_interface/differential_transmission.h

Lines changed: 2 additions & 2 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.
@@ -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]);

transmission_interface/include/transmission_interface/four_bar_linkage_transmission.h

Lines changed: 2 additions & 3 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.
@@ -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]);

transmission_interface/include/transmission_interface/simple_transmission.h

Lines changed: 2 additions & 2 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.
@@ -201,7 +201,7 @@ 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]);

transmission_interface/include/transmission_interface/transmission.h

Lines changed: 1 addition & 1 deletion
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.

transmission_interface/include/transmission_interface/transmission_interface.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,7 @@ class ActuatorToJointStateHandle : public TransmissionHandle<>
147147
void propagate()
148148
{
149149
transmission_->actuatorToJointPosition(actuator_data_, joint_data_);
150-
transmission_->actuatorToJointVelocity(actuator_data_, joint_data_);
150+
transmission_->actuatorToJoint(actuator_data_, joint_data_);
151151
transmission_->actuatorToJoint(actuator_data_, joint_data_);
152152
}
153153
/*\}*/
@@ -190,7 +190,7 @@ class ActuatorToJointVelocityHandle : public TransmissionHandle<>
190190
/** \brief Propagate actuator velocities to joint velocities for the stored transmission. */
191191
void propagate()
192192
{
193-
transmission_->actuatorToJointVelocity(actuator_data_, joint_data_);
193+
transmission_->actuatorToJoint(actuator_data_, joint_data_);
194194
}
195195
/*\}*/
196196
};

0 commit comments

Comments
 (0)