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
@@ -234,6 +243,10 @@ bool GazeboSimSystem::initSim(
234243
235244 sim::Entity simjoint = enableJoints[joint_name];
236245 this ->dataPtr ->joints_ [j].sim_joint = simjoint;
246+ this ->dataPtr ->joints_ [j].joint_type = _ecm.Component <sim::components::JointType>(
247+ simjoint)->Data ();
248+ this ->dataPtr ->joints_ [j].joint_axis = _ecm.Component <sim::components::JointAxis>(
249+ simjoint)->Data ();
237250
238251 // Create joint position component if one doesn't exist
239252 if (!_ecm.EntityHasComponentType (
@@ -251,12 +264,12 @@ bool GazeboSimSystem::initSim(
251264 _ecm.CreateComponent (simjoint, sim::components::JointVelocity ());
252265 }
253266
254- // Create joint force component if one doesn't exist
267+ // Create joint transmitted wrench component if one doesn't exist
255268 if (!_ecm.EntityHasComponentType (
256269 simjoint,
257- sim::components::JointForce ().TypeId ()))
270+ sim::components::JointTransmittedWrench ().TypeId ()))
258271 {
259- _ecm.CreateComponent (simjoint, sim::components::JointForce ());
272+ _ecm.CreateComponent (simjoint, sim::components::JointTransmittedWrench ());
260273 }
261274
262275 // Accept this joint and continue configuration
@@ -518,11 +531,10 @@ hardware_interface::return_type GazeboSimSystem::read(
518531 this ->dataPtr ->ecm ->Component <sim::components::JointVelocity>(
519532 this ->dataPtr ->joints_ [i].sim_joint );
520533
521- // TODO(ahcorde): Revisit this part gazebosim/ign-physics#124
522- // Get the joint force
523- // const auto * jointForce =
524- // _ecm.Component<sim::components::JointForce>(
525- // this->dataPtr->sim_joints_[j]);
534+ // Get the joint force via joint transmitted wrench
535+ const auto * jointWrench =
536+ this ->dataPtr ->ecm ->Component <sim::components::JointTransmittedWrench>(
537+ this ->dataPtr ->joints_ [i].sim_joint );
526538
527539 // Get the joint position
528540 const auto * jointPositions =
@@ -531,7 +543,19 @@ hardware_interface::return_type GazeboSimSystem::read(
531543
532544 this ->dataPtr ->joints_ [i].joint_position = jointPositions->Data ()[0 ];
533545 this ->dataPtr ->joints_ [i].joint_velocity = jointVelocity->Data ()[0 ];
534- // this->dataPtr->joint_effort_[j] = jointForce->Data()[0];
546+ gz::physics::Vector3d force_or_torque;
547+ if (this ->dataPtr ->joints_ [i].joint_type == sdf::JointType::PRISMATIC) {
548+ force_or_torque = {jointWrench->Data ().force ().x (),
549+ jointWrench->Data ().force ().y (), jointWrench->Data ().force ().z ()};
550+ } else { // REVOLUTE and CONTINUOUS
551+ force_or_torque = {jointWrench->Data ().torque ().x (),
552+ jointWrench->Data ().torque ().y (), jointWrench->Data ().torque ().z ()};
553+ }
554+ // Calculate the scalar effort along the joint axis
555+ this ->dataPtr ->joints_ [i].joint_effort = force_or_torque.dot (
556+ gz::physics::Vector3d{this ->dataPtr ->joints_ [i].joint_axis .Xyz ()[0 ],
557+ this ->dataPtr ->joints_ [i].joint_axis .Xyz ()[1 ],
558+ this ->dataPtr ->joints_ [i].joint_axis .Xyz ()[2 ]});
535559 }
536560
537561 for (unsigned int i = 0 ; i < this ->dataPtr ->imus_ .size (); ++i) {
0 commit comments