Skip to content

Commit fb1c767

Browse files
andreasBihlmaiermergify[bot]
authored andcommitted
use gz-physics#283 to implement joint_states/effort feedback (#186)
(cherry picked from commit cc66e73) # Conflicts: # gz_ros2_control/src/gz_system.cpp
1 parent 0289be6 commit fb1c767

File tree

1 file changed

+38
-11
lines changed

1 file changed

+38
-11
lines changed

gz_ros2_control/src/gz_system.cpp

Lines changed: 38 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -21,17 +21,23 @@
2121
#include <utility>
2222
#include <vector>
2323

24+
<<<<<<< HEAD
2425
#ifdef GZ_HEADERS
2526
#include <gz/msgs/imu.pb.h>
2627

28+
=======
29+
#include <gz/physics/Geometry.hh>
30+
>>>>>>> cc66e73 (use gz-physics#283 to implement joint_states/effort feedback (#186))
2731
#include <gz/sim/components/AngularVelocity.hh>
2832
#include <gz/sim/components/Imu.hh>
29-
#include <gz/sim/components/JointForce.hh>
33+
#include <gz/sim/components/JointAxis.hh>
3034
#include <gz/sim/components/JointForceCmd.hh>
3135
#include <gz/sim/components/JointPosition.hh>
3236
#include <gz/sim/components/JointPositionReset.hh>
33-
#include <gz/sim/components/JointVelocity.hh>
37+
#include <gz/sim/components/JointTransmittedWrench.hh>
38+
#include <gz/sim/components/JointType.hh>
3439
#include <gz/sim/components/JointVelocityCmd.hh>
40+
#include <gz/sim/components/JointVelocity.hh>
3541
#include <gz/sim/components/JointVelocityReset.hh>
3642
#include <gz/sim/components/LinearAcceleration.hh>
3743
#include <gz/sim/components/Name.hh>
@@ -70,6 +76,12 @@ struct jointData
7076
/// \brief Joint's names.
7177
std::string name;
7278

79+
/// \brief Joint's type.
80+
sdf::JointType joint_type;
81+
82+
/// \brief Joint's axis.
83+
sdf::JointAxis joint_axis;
84+
7385
/// \brief Current joint position
7486
double joint_position;
7587

@@ -237,6 +249,10 @@ bool GazeboSimSystem::initSim(
237249

238250
sim::Entity simjoint = enableJoints[joint_name];
239251
this->dataPtr->joints_[j].sim_joint = simjoint;
252+
this->dataPtr->joints_[j].joint_type = _ecm.Component<sim::components::JointType>(
253+
simjoint)->Data();
254+
this->dataPtr->joints_[j].joint_axis = _ecm.Component<sim::components::JointAxis>(
255+
simjoint)->Data();
240256

241257
// Create joint position component if one doesn't exist
242258
if (!_ecm.EntityHasComponentType(
@@ -254,12 +270,12 @@ bool GazeboSimSystem::initSim(
254270
_ecm.CreateComponent(simjoint, sim::components::JointVelocity());
255271
}
256272

257-
// Create joint force component if one doesn't exist
273+
// Create joint transmitted wrench component if one doesn't exist
258274
if (!_ecm.EntityHasComponentType(
259275
simjoint,
260-
sim::components::JointForce().TypeId()))
276+
sim::components::JointTransmittedWrench().TypeId()))
261277
{
262-
_ecm.CreateComponent(simjoint, sim::components::JointForce());
278+
_ecm.CreateComponent(simjoint, sim::components::JointTransmittedWrench());
263279
}
264280

265281
// Accept this joint and continue configuration
@@ -560,11 +576,10 @@ hardware_interface::return_type GazeboSimSystem::read(
560576
this->dataPtr->ecm->Component<sim::components::JointVelocity>(
561577
this->dataPtr->joints_[i].sim_joint);
562578

563-
// TODO(ahcorde): Revisit this part gazebosim/ign-physics#124
564-
// Get the joint force
565-
// const auto * jointForce =
566-
// _ecm.Component<sim::components::JointForce>(
567-
// this->dataPtr->sim_joints_[j]);
579+
// Get the joint force via joint transmitted wrench
580+
const auto * jointWrench =
581+
this->dataPtr->ecm->Component<sim::components::JointTransmittedWrench>(
582+
this->dataPtr->joints_[i].sim_joint);
568583

569584
// Get the joint position
570585
const auto * jointPositions =
@@ -573,7 +588,19 @@ hardware_interface::return_type GazeboSimSystem::read(
573588

574589
this->dataPtr->joints_[i].joint_position = jointPositions->Data()[0];
575590
this->dataPtr->joints_[i].joint_velocity = jointVelocity->Data()[0];
576-
// this->dataPtr->joint_effort_[j] = jointForce->Data()[0];
591+
gz::physics::Vector3d force_or_torque;
592+
if (this->dataPtr->joints_[i].joint_type == sdf::JointType::PRISMATIC) {
593+
force_or_torque = {jointWrench->Data().force().x(),
594+
jointWrench->Data().force().y(), jointWrench->Data().force().z()};
595+
} else { // REVOLUTE and CONTINUOUS
596+
force_or_torque = {jointWrench->Data().torque().x(),
597+
jointWrench->Data().torque().y(), jointWrench->Data().torque().z()};
598+
}
599+
// Calculate the scalar effort along the joint axis
600+
this->dataPtr->joints_[i].joint_effort = force_or_torque.dot(
601+
gz::physics::Vector3d{this->dataPtr->joints_[i].joint_axis.Xyz()[0],
602+
this->dataPtr->joints_[i].joint_axis.Xyz()[1],
603+
this->dataPtr->joints_[i].joint_axis.Xyz()[2]});
577604
}
578605

579606
for (unsigned int i = 0; i < this->dataPtr->imus_.size(); ++i) {

0 commit comments

Comments
 (0)