Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

gazebo_yarp_controlboard: Add coupling icub_left_hand_mk4 to model iCub mk4 left hand #620

Merged
merged 8 commits into from
Apr 4, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ The format of this document is based on [Keep a Changelog](https://keepachangelo

### Added
- In `gazebo_yarp_camera` parse the `yarpDeviceName` option to enable its use with `gazebo_yarp_robotinterface` (https://github.com/robotology/gazebo-yarp-plugins/pull/614).
- In `gazebo_yarp_controlboard` add the `icub_left_hand_mk4` coupling that models the iCub mk4 left hand (https://github.com/robotology/gazebo-yarp-plugins/pull/620).

### Changed
- Migrate the example models under the tutorial directory to avoid the use of implicit network wrapper servers, and use the `gazebo_yarp_robotinterface` plugin to spawn their network wrapper servers (https://github.com/robotology/gazebo-yarp-plugins/pull/615 and https://github.com/robotology/gazebo-yarp-plugins/pull/616).
Expand Down
26 changes: 26 additions & 0 deletions plugins/controlboard/include/yarp/dev/ControlBoardDriverCoupling.h
Original file line number Diff line number Diff line change
Expand Up @@ -197,4 +197,30 @@ class HandMk3CouplingHandler : public BaseCouplingHandler
std::vector<double> index_lut;
};

class HandMk4CouplingHandler : public BaseCouplingHandler
{

public:
HandMk4CouplingHandler (gazebo::physics::Model* model, yarp::sig::VectorOf<int> coupled_joints, std::vector<std::string> coupled_joint_names, std::vector<Range> coupled_joint_limits);

public:
bool decouplePos (yarp::sig::Vector& current_pos);
bool decoupleVel (yarp::sig::Vector& current_vel);
bool decoupleAcc (yarp::sig::Vector& current_acc);
bool decoupleTrq (yarp::sig::Vector& current_trq);

yarp::sig::Vector decoupleRefPos (yarp::sig::Vector& pos_ref);
yarp::sig::Vector decoupleRefVel (yarp::sig::Vector& vel_ref);
yarp::sig::Vector decoupleRefTrq (yarp::sig::Vector& trq_ref);

protected:
double decouple (double q2, std::vector<double>& lut);

const int LUTSIZE;

std::vector<double> thumb_lut;
std::vector<double> index_lut;
std::vector<double> pinkie_lut;
};

#endif //GAZEBOYARP_COUPLING_H
9 changes: 8 additions & 1 deletion plugins/controlboard/src/ControlBoardDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,8 @@ bool GazeboYarpControlBoardDriver::gazebo_init()
m_velocity_watchdog[j] = new Watchdog(0.200); //watchdog set to 200ms
}

yCDebug(GAZEBOCONTROLBOARD) << "done";
yCDebug(GAZEBOCONTROLBOARD) << "Trajectory successfully generated.";

for (size_t j = 0; j < m_numberOfJoints; ++j)
{
m_controlMode[j] = VOCAB_CM_POSITION;
Expand Down Expand Up @@ -330,6 +331,12 @@ bool GazeboYarpControlBoardDriver::gazebo_init()
m_coupling_handler.push_back(cpl);
yCInfo(GAZEBOCONTROLBOARD) << "using icub_hand_mk3";
}
else if (coupling_bottle->get(0).asString()=="icub_left_hand_mk4")
{
BaseCouplingHandler* cpl = new HandMk4CouplingHandler(m_robot,coupled_joints, coupled_joint_names, coupled_joint_limits);
m_coupling_handler.push_back(cpl);
yCInfo(GAZEBOCONTROLBOARD) << "using icub_left_hand_mk4";
}
else if (coupling_bottle->get(0).asString()=="none")
{
yCDebug(GAZEBOCONTROLBOARD) << "Just for test";
Expand Down
Loading