Skip to content

Commit c83f289

Browse files
use of gz-physics#283 to implement joint_states/effort feedback
1 parent 889837d commit c83f289

File tree

1 file changed

+21
-13
lines changed

1 file changed

+21
-13
lines changed

ign_ros2_control/src/ign_system.cpp

Lines changed: 21 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -25,11 +25,12 @@
2525

2626
#include <ignition/gazebo/components/AngularVelocity.hh>
2727
#include <ignition/gazebo/components/Imu.hh>
28-
#include <ignition/gazebo/components/JointForce.hh>
2928
#include <ignition/gazebo/components/JointForceCmd.hh>
3029
#include <ignition/gazebo/components/JointPosition.hh>
31-
#include <ignition/gazebo/components/JointVelocity.hh>
30+
#include <ignition/gazebo/components/JointTransmittedWrench.hh>
31+
#include <ignition/gazebo/components/JointType.hh>
3232
#include <ignition/gazebo/components/JointVelocityCmd.hh>
33+
#include <ignition/gazebo/components/JointVelocity.hh>
3334
#include <ignition/gazebo/components/LinearAcceleration.hh>
3435
#include <ignition/gazebo/components/Name.hh>
3536
#include <ignition/gazebo/components/ParentEntity.hh>
@@ -46,6 +47,9 @@ struct jointData
4647
/// \brief Joint's names.
4748
std::string name;
4849

50+
/// \brief Joint's type.
51+
sdf::JointType joint_type;
52+
4953
/// \brief Current joint position
5054
double joint_position;
5155

@@ -197,6 +201,7 @@ bool IgnitionSystem::initSim(
197201

198202
ignition::gazebo::Entity simjoint = enableJoints[joint_name];
199203
this->dataPtr->joints_[j].sim_joint = simjoint;
204+
this->dataPtr->joints_[j].joint_type = _ecm.Component<ignition::gazebo::components::JointType>(simjoint)->Data();
200205

201206
// Create joint position component if one doesn't exist
202207
if (!_ecm.EntityHasComponentType(
@@ -214,12 +219,12 @@ bool IgnitionSystem::initSim(
214219
_ecm.CreateComponent(simjoint, ignition::gazebo::components::JointVelocity());
215220
}
216221

217-
// Create joint force component if one doesn't exist
222+
// Create joint transmitted wrench component if one doesn't exist
218223
if (!_ecm.EntityHasComponentType(
219224
simjoint,
220-
ignition::gazebo::components::JointForce().TypeId()))
225+
ignition::gazebo::components::JointTransmittedWrench().TypeId()))
221226
{
222-
_ecm.CreateComponent(simjoint, ignition::gazebo::components::JointForce());
227+
_ecm.CreateComponent(simjoint, ignition::gazebo::components::JointTransmittedWrench());
223228
}
224229

225230
// Accept this joint and continue configuration
@@ -496,11 +501,10 @@ hardware_interface::return_type IgnitionSystem::read(
496501
this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocity>(
497502
this->dataPtr->joints_[i].sim_joint);
498503

499-
// TODO(ahcorde): Revisit this part ignitionrobotics/ign-physics#124
500-
// Get the joint force
501-
// const auto * jointForce =
502-
// _ecm.Component<ignition::gazebo::components::JointForce>(
503-
// this->dataPtr->sim_joints_[j]);
504+
// Get the joint force via joint transmitted wrench
505+
const auto * jointWrench =
506+
this->dataPtr->ecm->Component<ignition::gazebo::components::JointTransmittedWrench>(
507+
this->dataPtr->joints_[i].sim_joint);
504508

505509
// Get the joint position
506510
const auto * jointPositions =
@@ -509,7 +513,11 @@ hardware_interface::return_type IgnitionSystem::read(
509513

510514
this->dataPtr->joints_[i].joint_position = jointPositions->Data()[0];
511515
this->dataPtr->joints_[i].joint_velocity = jointVelocity->Data()[0];
512-
// this->dataPtr->joint_effort_[j] = jointForce->Data()[0];
516+
if (this->dataPtr->joints_[i].joint_type == sdf::JointType::PRISMATIC) {
517+
this->dataPtr->joints_[i].joint_effort = jointWrench->Data().force().z();
518+
} else { // REVOLUTE and CONTINUOUS
519+
this->dataPtr->joints_[i].joint_effort = jointWrench->Data().torque().z();
520+
}
513521
}
514522

515523
for (unsigned int i = 0; i < this->dataPtr->imus_.size(); ++i) {
@@ -699,8 +707,8 @@ hardware_interface::return_type IgnitionSystem::write(
699707
}
700708
}
701709
if (mimic_interface == "effort") {
702-
// TODO(ahcorde): Revisit this part ignitionrobotics/ign-physics#124
703-
// Get the joint force
710+
// TODO(ahb):
711+
// Get the joint force via joint transmitted wrench
704712
// const auto * jointForce =
705713
// _ecm.Component<ignition::gazebo::components::JointForce>(
706714
// this->dataPtr->sim_joints_[j]);

0 commit comments

Comments
 (0)