Skip to content

Commit c892802

Browse files
Nicogenetraversaro
andauthored
ControlBoardDriver: support use of IJointCoupling devices in gazebo_yarp_controlboard and drop support for hardcoded HandMK5 coupling (#671)
Co-authored-by: Silvio Traversaro <silvio@traversaro.it>
1 parent b57b299 commit c892802

10 files changed

+300
-475
lines changed

CHANGELOG.md

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,13 @@ The format of this document is based on [Keep a Changelog](https://keepachangelo
55

66
## [Unreleased]
77

8+
### Added
9+
- The `gazebo_yarp_controlboard` plugin gained support to load at runtime arbitrary couplings specified by a yarp device that exposes the [`yarp::dev::IJointCoupling`](https://github.com/robotology/yarp/blob/v3.9.0/src/libYARP_dev/src/yarp/dev/IJointCoupling.h#L16) interface. The name of the yarp device used to load the coupling is passed via the `device` parameter in the `COUPLING` group. For an example of PR that uses this new feature, check https://github.com/icub-tech-iit/ergocub-software/pull/178 .
10+
11+
### Removed
12+
13+
- The support for passing the `icub_hand_mk5` parameter in the `COUPLING` the `gazebo_yarp_controlboard` plugin was removed. This breaks compatibility with models contained in ergocub-software <= 0.6.0, to use those models use a newer version of ergocub-software.
14+
815
## [4.9.0] - 2023-10-31
916

1017
### Changed

CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ if(GAZEBO_YARP_PLUGINS_HAS_YARP_ROBOTINTERFACE)
4646
list(APPEND YARP_ADDITIONAL_COMPONENTS_REQUIRED "robotinterface")
4747
endif()
4848

49-
find_package(YARP 3.6 REQUIRED COMPONENTS os sig dev math idl_tools ${YARP_ADDITIONAL_COMPONENTS_REQUIRED})
49+
find_package(YARP 3.9 REQUIRED COMPONENTS os sig dev math idl_tools ${YARP_ADDITIONAL_COMPONENTS_REQUIRED})
5050
find_package(Gazebo REQUIRED)
5151
if (Gazebo_VERSION_MAJOR LESS 11.0)
5252
message(status "Gazebo version : " ${Gazebo_VERSION_MAJOR}.${Gazebo_VERSION_MINOR}.${Gazebo_VERSION_PATCH})
@@ -60,7 +60,7 @@ if(MSVC)
6060
# It is tipically better to use target_include_directories in place of
6161
# global include_directories, but in this case it is more compact to use include_directories
6262
include_directories(${OGRE_Paging_INCLUDE_DIRS})
63-
63+
6464
# Workaround for https://github.com/robotology/gazebo-yarp-plugins/issues/482
6565
add_definitions(-D__TBB_NO_IMPLICIT_LINKAGE=1)
6666
endif()

plugins/controlboard/include/yarp/dev/ControlBoardDriver.h

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include <yarp/dev/ControlBoardInterfaces.h>
1919
#include <yarp/dev/IControlMode.h>
2020
#include <yarp/dev/IInteractionMode.h>
21+
#include <yarp/dev/IJointCoupling.h>
2122
#include <yarp/dev/IRemoteVariables.h>
2223
#include <yarp/dev/IVirtualAnalogSensor.h>
2324
#include <yarp/sig/Vector.h>
@@ -372,6 +373,9 @@ class yarp::dev::GazeboYarpControlBoardDriver:
372373
std::vector<Range> m_jointPosLimits;
373374
std::vector<Range> m_jointVelLimits;
374375

376+
std::vector<Range> m_actuatedAxesPosLimits;
377+
std::vector<Range> m_actuatedAxesVelLimits;
378+
375379
/**
376380
* The zero position is the position of the GAZEBO joint that will be read as the starting one
377381
* i.e. getEncoder(j)=m_zeroPosition+gazebo.getEncoder(j);
@@ -410,11 +414,14 @@ class yarp::dev::GazeboYarpControlBoardDriver:
410414

411415
//trajectory generator
412416
std::vector<TrajectoryGenerator*> m_trajectory_generator;
413-
std::vector<BaseCouplingHandler*> m_coupling_handler;
417+
BaseCouplingHandler* m_coupling_handler{nullptr};
414418
std::vector<RampFilter*> m_speed_ramp_handler;
415419
std::vector<Watchdog*> m_velocity_watchdog;
416420
std::vector<Watchdog*> m_velocityControl;
417421

422+
yarp::dev::IJointCoupling* m_ijointcoupling{nullptr};
423+
yarp::dev::PolyDriver m_coupling_driver;
424+
418425

419426
yarp::sig::Vector m_trajectoryGenerationReferencePosition; /**< reference position for trajectory generation in position mode [Degrees] */
420427
yarp::sig::Vector m_trajectoryGenerationReferenceSpeed; /**< reference speed for trajectory generation in position mode [Degrees/Seconds]*/

plugins/controlboard/include/yarp/dev/ControlBoardDriverCoupling.h

Lines changed: 0 additions & 57 deletions
Original file line numberDiff line numberDiff line change
@@ -223,61 +223,4 @@ class HandMk4CouplingHandler : public BaseCouplingHandler
223223
std::vector<double> pinkie_lut;
224224
};
225225

226-
class HandMk5CouplingHandler : public BaseCouplingHandler
227-
{
228-
229-
public:
230-
HandMk5CouplingHandler (gazebo::physics::Model* model, yarp::sig::VectorOf<int> coupled_joints, std::vector<std::string> coupled_joint_names, std::vector<Range> coupled_joint_limits);
231-
232-
public:
233-
234-
bool parseFingerParameters(yarp::os::Bottle& hand_params);
235-
bool decouplePos (yarp::sig::Vector& current_pos);
236-
bool decoupleVel (yarp::sig::Vector& current_vel);
237-
bool decoupleAcc (yarp::sig::Vector& current_acc);
238-
bool decoupleTrq (yarp::sig::Vector& current_trq);
239-
240-
yarp::sig::Vector decoupleRefPos (yarp::sig::Vector& pos_ref);
241-
yarp::sig::Vector decoupleRefVel (yarp::sig::Vector& vel_ref, const yarp::sig::Vector& pos_feedback);
242-
yarp::sig::Vector decoupleRefTrq (yarp::sig::Vector& trq_ref);
243-
244-
private:
245-
/**
246-
* Parameters from https://icub-tech-iit.github.io/documentation/hands/hands_mk5_coupling
247-
*/
248-
struct FingerParameters
249-
{
250-
double L0x;
251-
double L0y;
252-
double q2bias;
253-
double q1off;
254-
double k;
255-
double d;
256-
double l;
257-
double b;
258-
};
259-
260-
std::map<std::string, FingerParameters> mFingerParameters;
261-
262-
/*
263-
* This method implements the law q2 = q2(q1) from
264-
* https://icub-tech-iit.github.io/documentation/hands/hands_mk5_coupling,
265-
* i.e., the absolute angle of the distal joint q2 with respect to the palm.
266-
*
267-
* The inputs q1 and the return value of the function are in degrees.
268-
*/
269-
double evaluateCoupledJoint(const double& q1, const std::string& finger_name);
270-
271-
/*
272-
* This method implements the law \frac{\partial{q2}}{\partial{q1}} from
273-
* https://icub-tech-iit.github.io/documentation/hands/hands_mk5_coupling,
274-
* i.e., the jacobian of the absolute angle of the distal joint q2 measured from the palm,
275-
* with respect to the proximal joint q1.
276-
*
277-
* The input q1 is in degrees.
278-
*/
279-
double evaluateCoupledJointJacobian(const double& q1, const std::string& finger_name);
280-
281-
};
282-
283226
#endif //GAZEBOYARP_COUPLING_H

0 commit comments

Comments
 (0)