2323#include < utility>
2424#include < vector>
2525
26+ #include < gz/physics/Geometry.hh>
2627#include < gz/sim/components/AngularVelocity.hh>
2728#include < gz/sim/components/Imu.hh>
28- #include < gz/sim/components/JointForce .hh>
29+ #include < gz/sim/components/JointAxis .hh>
2930#include < gz/sim/components/JointForceCmd.hh>
3031#include < gz/sim/components/JointPosition.hh>
3132#include < gz/sim/components/JointPositionReset.hh>
32- #include < gz/sim/components/JointVelocity.hh>
33+ #include < gz/sim/components/JointTransmittedWrench.hh>
34+ #include < gz/sim/components/JointType.hh>
3335#include < gz/sim/components/JointVelocityCmd.hh>
36+ #include < gz/sim/components/JointVelocity.hh>
3437#include < gz/sim/components/JointVelocityReset.hh>
3538#include < gz/sim/components/LinearAcceleration.hh>
3639#include < gz/sim/components/Name.hh>
@@ -50,6 +53,12 @@ struct jointData
5053 // / \brief Joint's names.
5154 std::string name;
5255
56+ // / \brief Joint's type.
57+ sdf::JointType joint_type;
58+
59+ // / \brief Joint's axis.
60+ sdf::JointAxis joint_axis;
61+
5362 // / \brief Current joint position
5463 double joint_position;
5564
@@ -250,6 +259,10 @@ bool GazeboSimSystem::initSim(
250259
251260 sim::Entity simjoint = enableJoints[joint_name];
252261 this ->dataPtr ->joints_ [j].sim_joint = simjoint;
262+ this ->dataPtr ->joints_ [j].joint_type = _ecm.Component <sim::components::JointType>(
263+ simjoint)->Data ();
264+ this ->dataPtr ->joints_ [j].joint_axis = _ecm.Component <sim::components::JointAxis>(
265+ simjoint)->Data ();
253266
254267 // Create joint position component if one doesn't exist
255268 if (!_ecm.EntityHasComponentType (
@@ -267,12 +280,12 @@ bool GazeboSimSystem::initSim(
267280 _ecm.CreateComponent (simjoint, sim::components::JointVelocity ());
268281 }
269282
270- // Create joint force component if one doesn't exist
283+ // Create joint transmitted wrench component if one doesn't exist
271284 if (!_ecm.EntityHasComponentType (
272285 simjoint,
273- sim::components::JointForce ().TypeId ()))
286+ sim::components::JointTransmittedWrench ().TypeId ()))
274287 {
275- _ecm.CreateComponent (simjoint, sim::components::JointForce ());
288+ _ecm.CreateComponent (simjoint, sim::components::JointTransmittedWrench ());
276289 }
277290
278291 // Accept this joint and continue configuration
@@ -533,11 +546,10 @@ hardware_interface::return_type GazeboSimSystem::read(
533546 this ->dataPtr ->ecm ->Component <sim::components::JointVelocity>(
534547 this ->dataPtr ->joints_ [i].sim_joint );
535548
536- // TODO(ahcorde): Revisit this part gazebosim/ign-physics#124
537- // Get the joint force
538- // const auto * jointForce =
539- // _ecm.Component<sim::components::JointForce>(
540- // this->dataPtr->sim_joints_[j]);
549+ // Get the joint force via joint transmitted wrench
550+ const auto * jointWrench =
551+ this ->dataPtr ->ecm ->Component <sim::components::JointTransmittedWrench>(
552+ this ->dataPtr ->joints_ [i].sim_joint );
541553
542554 // Get the joint position
543555 const auto * jointPositions =
@@ -546,7 +558,19 @@ hardware_interface::return_type GazeboSimSystem::read(
546558
547559 this ->dataPtr ->joints_ [i].joint_position = jointPositions->Data ()[0 ];
548560 this ->dataPtr ->joints_ [i].joint_velocity = jointVelocity->Data ()[0 ];
549- // this->dataPtr->joint_effort_[j] = jointForce->Data()[0];
561+ gz::physics::Vector3d force_or_torque;
562+ if (this ->dataPtr ->joints_ [i].joint_type == sdf::JointType::PRISMATIC) {
563+ force_or_torque = {jointWrench->Data ().force ().x (),
564+ jointWrench->Data ().force ().y (), jointWrench->Data ().force ().z ()};
565+ } else { // REVOLUTE and CONTINUOUS
566+ force_or_torque = {jointWrench->Data ().torque ().x (),
567+ jointWrench->Data ().torque ().y (), jointWrench->Data ().torque ().z ()};
568+ }
569+ // Calculate the scalar effort along the joint axis
570+ this ->dataPtr ->joints_ [i].joint_effort = force_or_torque.dot (
571+ gz::physics::Vector3d{this ->dataPtr ->joints_ [i].joint_axis .Xyz ()[0 ],
572+ this ->dataPtr ->joints_ [i].joint_axis .Xyz ()[1 ],
573+ this ->dataPtr ->joints_ [i].joint_axis .Xyz ()[2 ]});
550574 }
551575
552576 for (unsigned int i = 0 ; i < this ->dataPtr ->imus_ .size (); ++i) {
0 commit comments