24 ROS_INFO_STREAM (
"Ros parameter for rate not found, I'm setting the default rate of 100 Hz" );
38 _ee = std::make_shared<ROSEE::EEInterface> ( p );
40 for (
auto&
f :
_ee->getFingers() ) {
62 std::string actionGraspingCommandName;
63 _nh.
param<std::string>(
"/rosee/rosAction_grasping_command", actionGraspingCommandName,
"action_command");
75 std::string motor_reference_topic =
"motor_reference_pos";
76 const int motor_reference_queue = 10;
80 _motor_reference_pub = _nh.advertise<sensor_msgs::JointState> ( motor_reference_topic, motor_reference_queue );
81 _motors_num = _motors_names.size();
83 _mr_msg.name = _motors_names;
84 _mr_msg.position.resize ( _motors_num );
85 _mr_msg.velocity.resize ( _motors_num );
86 _mr_msg.effort.resize ( _motors_num );
94 const double DAMPING_FACT = 1.0;
95 const double BW_MEDIUM = 2.0;
96 double omega = 2.0 *
M_PI * BW_MEDIUM;
98 _filt_q.setDamping ( DAMPING_FACT );
99 _filt_q.setTimeStep ( _period );
100 _filt_q.setOmega ( omega );
103 _qref.resize ( _motors_num );
104 _qref_optional.resize ( _motors_num );
105 _qref_optional.setZero();
109 _filt_q.reset ( _qref );
118 mapActionHandlerPtr = std::make_shared<ROSEE::MapActionHandler>();
119 mapActionHandlerPtr->parseAllActions(folderForActions);
122 _pinchParsedMap = mapActionHandlerPtr->getPrimitiveMap(
"pinchTight");
125 if (mapActionHandlerPtr->getPrimitiveMap(ROSEE::ActionPrimitive::Type::PinchLoose).size()>0) {
127 _pinchLooseParsedMap = mapActionHandlerPtr->getPrimitiveMap(ROSEE::ActionPrimitive::Type::PinchLoose).at(0);
131 _trigParsedMap = mapActionHandlerPtr->getPrimitiveMap(
"trig");
132 _tipFlexParsedMap = mapActionHandlerPtr->getPrimitiveMap(
"tipFlex");
133 _fingFlexParsedMap = mapActionHandlerPtr->getPrimitiveMap(
"fingFlex");
137 for (
auto &i : _pinchParsedMap ) {
141 for (
auto &i : _pinchLooseParsedMap ) {
145 for (
auto &i : _trigParsedMap ) {
149 for (
auto &i : _tipFlexParsedMap ) {
153 for (
auto &i : _fingFlexParsedMap ) {
158 _graspParsed = mapActionHandlerPtr->getGeneric(
"grasp");
162 if (_graspParsed !=
nullptr) {
163 _graspParsed->print();
172 std::string topic_name_js =
"/ros_end_effector/joint_states";
174 ROS_INFO_STREAM (
"Getting joint pos from '" << topic_name_js <<
"'" );
176 _joint_state_sub = _nh.subscribe (topic_name_js, 1,
183 for (
int i=0; i< msg->name.size(); i++) {
184 std::vector <double> one_dof { msg->position.at(i) };
185 _joint_actual_pos[msg->name.at(i)] = one_dof;
193 rosee_msg::ROSEEActionControl goal = _ros_action_server->getGoal();
195 timed_requested =
false;
197 if (goal.action_type != ROSEE::Action::Type::Timed){
198 if (goal.percentage < 0 || goal.percentage > 1) {
199 ROS_ERROR_STREAM (
"Received an action-goal with percentage " << goal.percentage <<
200 " Please insert a value between 0 (for 0%) and 1 (for 100%) ");
201 _ros_action_server->abortGoal(
"Percentage not valid");
211 switch (goal.action_type) {
213 case ROSEE::Action::Type::Primitive :
217 if (primitive ==
nullptr) {
219 _ros_action_server->abortGoal(
"Primitive Action not found");
223 _motor_position_goal = primitive->getJointPos();
224 _motor_involved_mask = primitive->getJointsInvolvedCount();
228 case ROSEE::Action::Type::Generic :
229 case ROSEE::Action::Type::Composed :
233 if (
generic ==
nullptr) {
235 _ros_action_server->abortGoal(
"Generic Action not found");
239 _motor_position_goal =
generic->getJointPos();
240 _motor_involved_mask =
generic->getJointsInvolvedCount();
244 case ROSEE::Action::Type::Timed : {
248 timedAction = mapActionHandlerPtr->getTimed(goal.action_name);
250 if (timedAction ==
nullptr) {
252 _ros_action_server->abortGoal(
"Timed Action not found");
256 timed_requested =
true;
258 _motor_position_goal = timedAction->getAllJointPos().at(0);
259 _motor_involved_mask = timedAction->getJointCountAction(
260 timedAction->getInnerActionsNames().at(0));
266 case ROSEE::Action::Type::None :
268 ROS_ERROR_STREAM (
"Received an action-goal of type None (" << goal.action_type <<
269 ") which is a no-type. Please use valid Action::Type ");
270 _ros_action_server->abortGoal(
"Invalid type NONE");
275 ROS_ERROR_STREAM (
"Received an action-goal of type " << goal.action_type <<
276 " which I do not recognize. Please use valid Action::Type ");
277 _ros_action_server->abortGoal(
"Invalid type " + std::to_string(goal.action_type) );
283 _qref_optional.setZero();
284 if (goal.optional_motors_names.size() != 0) {
285 readOptionalCommands(goal.optional_motors_names, goal.optional_motors_commands);
288 return updateRefGoal(goal.percentage);
293 std::vector<std::string> motors_names, std::vector<double> motors_commands) {
297 if (motors_names.size() != motors_commands.size() &&
298 motors_names.size() != _motors_num) {
299 ROS_ERROR_STREAM (
"In receiving the goal command, the optional field is formed badly: "
300 <<
"optional_motors_names and optional_motors_commands and number of motors have different size ("
301 << motors_names.size() <<
" and " << motors_commands.size() <<
" and " << _motors_num
302 <<
" respectively). I will ignore the optional command");
307 for (
int i=0; i<motors_names.size(); i++) {
310 _ee->getInternalIdForJoint ( motors_names.at(i),
id );
313 _qref_optional[id] = motors_commands.at(i);
317 ROS_WARN_STREAM (
"Trying to send an optional command to motor: " << motors_names.at(i)
318 <<
" which is not defined" );
330 normGoalFromInitialPos = 0;
331 for (
auto it : _motor_involved_mask ) {
333 if ( it.second != 0 ) {
335 _ee->getInternalIdForJoint ( it.first,
id );
339 _qref[id] = _motor_position_goal.at ( it.first ).at ( 0 ) * percentage;
342 normGoalFromInitialPos += pow (_qref[
id] - _joint_actual_pos.at(it.first).at(0), 2 ) ;
345 ROS_WARN_STREAM (
"Trying to move Joint: " << it.first <<
" with ID: " <<
id );
346 _ros_action_server->abortGoal(
"Invalid Joint id" );
351 normGoalFromInitialPos = sqrt(normGoalFromInitialPos);
353 if (timed_requested) {
359 if (timed_index == 0) {
360 msToWait = timedAction->getAllActionMargins().at(timed_index).first;
362 }
else if (timed_index < timedAction->getInnerActionsNames().size()) {
363 msToWait = timedAction->getAllActionMargins().at(timed_index-1).second +
364 timedAction->getAllActionMargins().at(timed_index).first;
376 double actualNorm = 0;
378 for (
auto it : _motor_involved_mask ) {
380 if ( it.second != 0 ) {
382 _ee->getInternalIdForJoint ( it.first,
id );
386 actualNorm += pow ( _qref[
id] - _joint_actual_pos.at(it.first).at(0) , 2 );
390 ROS_ERROR_STREAM (
"YOU SHOULD NOT BE HERE, previous error should stop execution");
394 actualNorm = sqrt(actualNorm);
396 double actualCompletationPercentage;
398 if (actualNorm < _ros_action_server->getWantedNormError()) {
399 actualCompletationPercentage = 100;
403 actualCompletationPercentage =
404 (((actualNorm - normGoalFromInitialPos) * (100-0)) / (0 - normGoalFromInitialPos)) + 0;
407 _ros_action_server->sendFeedback(actualCompletationPercentage, currentAction);
408 return actualCompletationPercentage;
415 _mr_msg.header.seq = _seq_id++;
417 _qref_filtered = _filt_q.process ( _qref );
420 for (
const auto& motor_name : _motors_names ) {
423 _ee->getInternalIdForJoint ( motor_name,
id );
424 _mr_msg.name[id] = motor_name;
425 _mr_msg.position[id] =_qref_filtered[id] ;
426 _mr_msg.effort[id] = _qref_optional[id];
429 _motor_reference_pub.publish ( _mr_msg );
437 if (_ros_action_server->hasNewGoal()) {
441 }
else if (_ros_action_server->hasGoal()) {
443 if (! timed_requested ) {
445 if (sendFeedbackGoal() >= 100) {
447 _ros_action_server->sendComplete();
452 if ( sendFeedbackGoal(timedAction->getInnerActionsNames().at(timed_index)) >= 100 ) {
454 if (timed_index == timedAction->getInnerActionsNames().size()-1) {
457 _ros_action_server->sendComplete();
458 timed_requested =
false;
461 timer.elapsed_time<
double, std::chrono::milliseconds>() >
462 (timedAction->getAllActionMargins().at(timed_index).second*1000) ) {
471 _motor_position_goal = timedAction->getAllJointPos().at(timed_index);
472 _motor_involved_mask = timedAction->getAllJointCountAction().at(timed_index);
482 if (timed_requested) {
483 if (timer.elapsed_time<
double, std::chrono::milliseconds>() > msToWait ) {
484 publish_motor_reference();
491 publish_motor_reference();