cob_teleop.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #include <ros/ros.h>
18 
20 #include <cob_light/LightModes.h>
21 #include <cob_light/SetLightModeAction.h>
22 #include <cob_script_server/ScriptAction.h>
23 #include <cob_sound/SayAction.h>
24 #include <cob_actions/SetStringAction.h>
25 #include <cob_actions/SetStringGoal.h>
26 #include <geometry_msgs/Twist.h>
27 #include <sensor_msgs/JointState.h>
28 #include <sensor_msgs/Joy.h>
29 #include <sensor_msgs/JoyFeedbackArray.h>
30 #include <std_msgs/Float64MultiArray.h>
31 #include <std_msgs/ColorRGBA.h>
32 #include <std_srvs/Trigger.h>
33 #include <XmlRpcValue.h>
34 
35 class CobTeleop
36 {
37 public:
38 
40  {
41  std::string key;
42  std::string twist_topic_name;
44  std::string vel_group_topic_name;
45  std::string sss_default_target;
46  std::vector<double> joint_velocity;
47  std::vector<double> twist_max_vel; //max_vx_, max_vy_, max_vz_, max_rotx_, max_roty_, max_rotz_
48  std::vector<double> twist_max_acc; //max_ax_, max_ay_, max_arotz_
52  };
53 
54  std::map<std::string,component_config> component_config_;
55 
56  //axis
59 
60  //buttons
61  //mode 1: Base
65  //mode 2: Trajectory controller (to default target position using sss.move)
66  //mode 3: Velocity group controller
71  //mode 4: Twist controller
72 
73  //common
78  bool safe_mode_;
79  double publish_freq_;
83  int mode_;
84  std::string joy_config_switch_;
87 
90  ros::Subscriber joy_sub_; //subscribe topic joy
91  ros::Subscriber joint_states_sub_; //subscribe topic joint_states
92 
95  cob_script_server::ScriptGoal script_goal_;
96 
100  std::string sound_action_name_;
101 
105  std::string light_action_name_;
106 
109  std::string dock_action_name_;
110 
113  std::string undock_action_name_;
114 
115  cob_light::SetLightModeGoal confirm_light_goal_;
116  cob_light::SetLightModeGoal error_light_goal_;
117 
118  std::vector<double> vel_old_;
119  std::vector<double> vel_req_;
120  std::vector<double> vel_base_;
122 
124  void init();
125  void updateBase();
126  void say(std::string text, bool blocking);
127  void setLight(int mode);
128  void joy_cb(const sensor_msgs::Joy::ConstPtr &joy_msg);
129  sensor_msgs::JoyFeedbackArray switch_mode();
130 };
131 
133 {
134  if(n_.hasParam("components"))
135  {
136  ROS_DEBUG("components found ");
137  n_.getParam("components", components_);
139  {
140  ROS_DEBUG("components are of type struct with size %d",(int)components_.size());
141  for(std::map<std::string,XmlRpc::XmlRpcValue>::iterator p=components_.begin();p!=components_.end();++p)
142  {
143  std::string comp_name = p->first;
144  ROS_DEBUG("component name: %s",comp_name.c_str());
145  XmlRpc::XmlRpcValue comp_struc = p->second;
146  if(comp_struc.getType() != XmlRpc::XmlRpcValue::TypeStruct)
147  {
148  ROS_WARN("invalid component, name: %s",comp_name.c_str());
149  }
150  component_config tempComponent;
151  for(std::map<std::string,XmlRpc::XmlRpcValue>::iterator ps=comp_struc.begin();ps!=comp_struc.end();++ps)
152  {
153  std::string par_name = ps->first;
154  ROS_DEBUG("par name: %s",par_name.c_str());
155  if(par_name.compare("twist_topic_name")==0)
156  {
157  ROS_DEBUG("twist topic name found");
158  XmlRpc::XmlRpcValue twist_topic_name = ps->second;
159  ROS_ASSERT(twist_topic_name.getType() == XmlRpc::XmlRpcValue::TypeString);
160  std::string s((std::string)twist_topic_name);
161  ROS_DEBUG("twist_topic_name found = %s",s.c_str());
162  tempComponent.twist_topic_name = s;
163  tempComponent.twist_controller_publisher_ = n_.advertise<geometry_msgs::Twist>((s),1);
164  }
165  if(par_name.compare("twist_safety_topic_name")==0)
166  {
167  ROS_DEBUG("twist saftey topic name found");
168  XmlRpc::XmlRpcValue twist_safety_topic_name= ps->second;
169  ROS_ASSERT(twist_safety_topic_name.getType() == XmlRpc::XmlRpcValue::TypeString);
170  std::string s((std::string)twist_safety_topic_name);
171  ROS_DEBUG("twist_safety_topic_name found = %s",s.c_str());
172  tempComponent.twist_safety_topic_name = s;
173  tempComponent.twist_safety_controller_publisher_ = n_.advertise<geometry_msgs::Twist>((s),1);
174  }
175  else if(par_name.compare("velocity_topic_name")==0)
176  {
177  ROS_DEBUG("topic name found");
178  XmlRpc::XmlRpcValue vel_group_topic_name = ps->second;
179  ROS_ASSERT(vel_group_topic_name.getType() == XmlRpc::XmlRpcValue::TypeString);
180  std::string s((std::string)vel_group_topic_name);
181  ROS_DEBUG("topic_name found = %s",s.c_str());
182  tempComponent.vel_group_topic_name = s;
183  tempComponent.vel_group_controller_publisher_ = n_.advertise<std_msgs::Float64MultiArray>((s),1);
184  }
185  else if(par_name.compare("sss_default_target")==0)
186  {
187  ROS_DEBUG("default target position found");
188  XmlRpc::XmlRpcValue sss_default_target = ps->second;
189  ROS_ASSERT(sss_default_target.getType() == XmlRpc::XmlRpcValue::TypeString);
190  std::string s((std::string)sss_default_target);
191  ROS_DEBUG("sss_default_target found = %s",s.c_str());
192  tempComponent.sss_default_target = s;
193  }
194  else if(par_name.compare("joint_velocity")==0)
195  {
196  ROS_DEBUG("joint vels found");
197  XmlRpc::XmlRpcValue joint_velocity = ps->second;
199  ROS_DEBUG("joint_velocity.size: %d \n", joint_velocity.size());
200  for(int i=0;i<joint_velocity.size();i++)
201  {
202  ROS_ASSERT(joint_velocity[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
203  double vel((double)joint_velocity[i]);
204  ROS_DEBUG("joint_velocity found = %f",vel);
205  tempComponent.joint_velocity.push_back(vel);
206  }
207  }
208  else if(par_name.compare("twist_max_velocity")==0)
209  {
210  ROS_DEBUG("max Velocity found");
211  XmlRpc::XmlRpcValue twist_max_velocity = ps->second;
212  ROS_ASSERT(twist_max_velocity.getType() == XmlRpc::XmlRpcValue::TypeArray);
213  ROS_DEBUG("twist_max_velocity.size: %d \n", twist_max_velocity.size());
214  for(int i=0;i<twist_max_velocity.size();i++)
215  {
216  ROS_ASSERT(twist_max_velocity[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
217  double vel((double)twist_max_velocity[i]);
218  ROS_DEBUG("twist_max_velocity found = %f",vel);
219  tempComponent.twist_max_vel.push_back(vel);
220  }
221  }
222  else if(par_name.compare("twist_max_acc")==0)
223  {
224  ROS_DEBUG("max Velocity found");
225  XmlRpc::XmlRpcValue twist_max_acc = ps->second;
227  ROS_DEBUG("twist_max_acc.size: %d \n", twist_max_acc.size());
228  for(int i=0;i<twist_max_acc.size();i++)
229  {
230  ROS_ASSERT(twist_max_acc[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
231  double vel((double)twist_max_acc[i]);
232  ROS_DEBUG("twist_max_acc found = %f",vel);
233  tempComponent.twist_max_acc.push_back(vel);
234  }
235  }
236  }
237  ROS_DEBUG("%s module stored",comp_name.c_str());
238  component_config_.insert(std::pair<std::string,component_config>(comp_name,tempComponent));
239  }
240  }
241  }
242 
243  sss_client_ = new ScriptClient_("/script_server", true);
244  n_.param<bool>("enable_sound", enable_sound_, false);
245  n_.param<std::string>("sound_action_name", sound_action_name_, "/sound/say");
247 
248  n_.param<bool>("enable_light", enable_light_, false);
249  n_.param<std::string>("light_action_name", light_action_name_, "set_light");
251 
252  n_.param<std::string>("dock_action_name", dock_action_name_, "/docker_control/dock");
254  n_.param<std::string>("undock_action_name", undock_action_name_, "/docker_control/undock");
256 
257  vel_req_.resize(component_config_["base"].twist_max_acc.size());
258  vel_old_.resize(component_config_["base"].twist_max_acc.size());
259  vel_base_.resize(component_config_["base"].twist_max_acc.size());
260  for(unsigned int i=0; i<component_config_["base"].twist_max_acc.size(); i++)
261  {
262  vel_old_[i]=0;
263  vel_req_[i]=0;
264  }
265 }
266 
267 sensor_msgs::JoyFeedbackArray CobTeleop::switch_mode()
268 {
269  ++mode_;
270 
271  if (mode_ > joy_num_modes_)
272  {
273  mode_ = 1;
274  }
275 
276  std::string saytext;
277  if (mode_ == 1)
278  {
279  ROS_INFO("Switched to mode 1: move the base using twist controller");
280  saytext = "Base mode";
281  }
282  if (mode_ == 2)
283  {
284  ROS_INFO("Switched to mode 2: move the actuators to a default position (Trajectory controller)");
285  saytext = "Default position mode";
286  }
287  if(mode_ == 3)
288  {
289  ROS_INFO("Switched to mode 3: move the actuators using joint group velocity controller");
290  saytext = "Velocity mode";
291  }
292  if(mode_ == 4)
293  {
294  ROS_INFO("Switched to mode 4: move the actuators in cartesian mode using twist controller");
295  saytext = "Cartesian mode";
296  }
297 
298  setLight(mode_);
299  say(saytext, false);
300 
302 
303  sensor_msgs::JoyFeedbackArray joy_fb;
304  joy_fb.array.resize(4);
305  for (unsigned int i=0; i<4; i++)
306  {
307  joy_fb.array[i].type=0;
308  joy_fb.array[i].id=i;
309  joy_fb.array[i].intensity=static_cast<int>(LEDS_[i]);
310  }
311  return joy_fb;
312 }
313 
315 {
316  if (joy_active_)
317  {
318  if(mode_==1)
319  {
320  double dt = 1.0/double(publish_freq_);
321  geometry_msgs::Twist base_cmd;
322  if(!joy_active_)
323  {
324  for(unsigned int i=0; i<3; i++)
325  {
326  vel_old_[i]=0;
327  vel_req_[i]=0;
328  }
329  }
330 
331  if(apply_ramp_)
332  {
333  for( int i =0; i<3; i++)
334  {
335  // filter v with ramp
336  if ((vel_req_[i]-vel_old_[i])/dt > component_config_["base"].twist_max_acc[i])
337  {
338  vel_base_[i] = vel_old_[i] + component_config_["base"].twist_max_acc[i]*dt;
339  }
340  else if((vel_req_[i]-vel_old_[i])/dt < -component_config_["base"].twist_max_acc[i])
341  {
342  vel_base_[i] = vel_old_[i] - component_config_["base"].twist_max_acc[i]*dt;
343  }
344  else
345  {
346  vel_base_[i] = vel_req_[i];
347  }
348  vel_old_[i] = vel_base_[i];
349  }
350  }
351  else
352  {
353  vel_base_[0] = vel_req_[0];
354  vel_base_[1] = vel_req_[1];
355  vel_base_[2] = vel_req_[2];
356  }
357  base_cmd.linear.x = vel_base_[0];
358  base_cmd.linear.y = vel_base_[1];
359  base_cmd.angular.z = vel_base_[2];
360  if (safe_mode_)
361  {
362  component_config_["base"].twist_safety_controller_publisher_.publish(base_cmd);
363  }
364  else
365  {
366  component_config_["base"].twist_controller_publisher_.publish(base_cmd);
367  }
368  }
369  }
370 }
371 
372 void CobTeleop::say(std::string text, bool blocking)
373 {
374  if(enable_sound_)
375  {
376  cob_sound::SayGoal say_goal;
377  say_goal.text = text;
378  say_client_->sendGoal(say_goal);
379  if (blocking)
380  {
382  }
383  }
384 }
385 
387 {
388  if(enable_light_)
389  {
390  cob_light::LightMode light;
391  light.mode = cob_light::LightModes::FLASH;
392  light.frequency = 5;
393  light.priority = 2;
394  std_msgs::ColorRGBA color;
395  color.r = 0;
396  color.g = 1;
397  color.b = 0;
398  color.a = 1;
399  light.pulses = mode;
400  light.colors.push_back(color);
401  cob_light::SetLightModeGoal light_goal;
402  light_goal.mode = light;
403  setlight_client_->sendGoal(light_goal);
404  }
405 }
406 
407 void CobTeleop::joy_cb(const sensor_msgs::Joy::ConstPtr &joy_msg)
408 {
409  if(deadman_button_>=0 && deadman_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[deadman_button_]==1)
410  {
411  ROS_DEBUG("joystick is active");
412  }
413  else
414  {
415  for(unsigned int i=0; i<component_config_["base"].twist_max_acc.size(); i++)
416  {
417  vel_req_[i]=0;
418  vel_old_[i]=0;
419  }
420  ROS_DEBUG("joystick is not active");
421  joy_active_ = false;
422  return;
423  }
424 
425  if(mode_switch_button_>=0 && mode_switch_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[mode_switch_button_]==1)
426  {
427  ROS_INFO("Switch mode button pressed");
428  switch_mode();
429  }
430 
431  if(safety_button_>=0 && safety_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[safety_button_]==1)
432  {
433  safe_mode_ = false;
434  }else
435  {
436  safe_mode_ = true;
437  }
438 
439  if(joy_config_switch_.compare("X") == 0 && axis_run_ < joy_msg->axes.size())
440  {
441  if(!axis_run_updated_)
442  {
443  if(joy_msg->axes[axis_run_] != 0)
444  axis_run_updated_ = true;
445  else
446  run_factor_ = 1.0;
447  }
449  {
450  run_factor_ = 1 + ((run_factor_param_ - 1.0) / -2.0) * (joy_msg->axes[axis_run_] - 1.0);
451  }
452  }
453  else if(run_button_>=0 && run_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[run_button_]>1)
454  {
456  }
457  else //button release
458  {
459  run_factor_ = 1.0;
460  }
461 
463  {
464  ROS_INFO("Waiting for script server");
465  return;
466  }
467 
468  if(init_button_>=0 && init_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[init_button_]==1)
469  {
470  ROS_INFO("Init and recover");
471  say("init and recover", true);
472 
473  for(std::map<std::string,XmlRpc::XmlRpcValue>::iterator p=components_.begin();p!=components_.end();++p)
474  {
475  std::string comp_name = p->first;
476 
477  ROS_INFO("Init %s",comp_name.c_str());
478  std::string saytext = comp_name;
479  std::replace(saytext.begin(), saytext.end(), '_', ' ');
480  say(saytext, true);
481  script_goal_.component_name = comp_name.c_str();
482  script_goal_.function_name="init";
485  if(sss_client_->getResult()->error_code != 0)
486  {
487  std::string saytext = "Init " + comp_name + " failed";
488  std::replace(saytext.begin(), saytext.end(), '_', ' ');
489  say(saytext, true);
490  }
491 
492  ROS_INFO("Recover %s",comp_name.c_str());
493  script_goal_.function_name="recover";
496  if(sss_client_->getResult()->error_code != 0)
497  {
498  std::string saytext = "Recover " + comp_name + " failed";
499  std::replace(saytext.begin(), saytext.end(), '_', ' ');
500  say(saytext, true);
501 
502  }
503  }
504 
505  say("go", true);
506  }
507 
508  //-------MODE 1
509  if (mode_==1)
510  {
511  ROS_DEBUG("Mode 1: Move the base using twist controller");
512  if(dock_button_>=0 && dock_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[dock_button_]==1)
513  {
517  {
518  ROS_DEBUG_STREAM("docking already in progress: "<<state.getText());
520  return;
521  }
522  dock_client_->sendGoal(cob_actions::SetStringGoal());
524  }
525 
526  if(undock_button_>=0 && undock_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[undock_button_]==1)
527  {
531  {
532  ROS_DEBUG_STREAM("undocking already in progress: "<<state.getText());
534  return;
535  }
536  undock_client_->sendGoal(cob_actions::SetStringGoal());
538  }
539 
540  if(axis_vx_>=0 && axis_vx_<(int)joy_msg->axes.size())
541  {
542  joy_active_ = true;
543  vel_req_[0] = joy_msg->axes[axis_vx_]*component_config_["base"].twist_max_vel[0]*run_factor_;
544  }
545  else
546  {
547  vel_req_[0] =0.0;
548  }
549  if(axis_vy_>=0 && axis_vy_<(int)joy_msg->axes.size())
550  {
551  joy_active_ = true;
552  vel_req_[1] = joy_msg->axes[axis_vy_]*component_config_["base"].twist_max_vel[1]*run_factor_;
553  }
554  else
555  {
556  vel_req_[1] = 0.0;
557  }
558  if(axis_yaw_>=0 && axis_yaw_<(int)joy_msg->axes.size())
559  {
560  joy_active_ = true;
561  vel_req_[2] = joy_msg->axes[axis_yaw_]*component_config_["base"].twist_max_vel[2]*run_factor_;
562  }
563  else
564  {
565  vel_req_[2] = 0.0;
566  }
567  }
568 
569  //-------MODE 2
570  if (mode_==2)
571  {
572  ROS_DEBUG("Mode 2: Move the actuators to a default position (Trajectory controller)");
573 
574  for(std::map<std::string,XmlRpc::XmlRpcValue>::iterator p=components_.begin();p!=components_.end();++p)
575  {
576  int component_sss_default_target_button_temp = -1;
577  std::string comp_name = p->first;
578  std::string component_sss_default_target_button = comp_name + "_sss_default_target_button";
579  n_.getParam(component_sss_default_target_button,component_sss_default_target_button_temp);
580  if (component_sss_default_target_button_temp == -1)
581  {
582  ROS_DEBUG("%s_sss_default_target_button parameter not defined",comp_name.c_str());
583  }
584  if(component_sss_default_target_button_temp>=0 && component_sss_default_target_button_temp<(int)joy_msg->buttons.size() && joy_msg->buttons[component_sss_default_target_button_temp]==1)
585  {
586  script_goal_.component_name = comp_name;
587  script_goal_.function_name = "move";
588  script_goal_.parameter_name = component_config_[comp_name].sss_default_target.c_str();
589  ROS_INFO("Move %s to %s",comp_name.c_str(), component_config_[comp_name].sss_default_target.c_str());
590  std::string saytext = "Move " + comp_name + " to " + script_goal_.parameter_name;
591  std::replace(saytext.begin(), saytext.end(), '_', ' ');
592  say(saytext, true);
594  }
595  }
596  }
597 
598  //-------MODE 3
599  if (mode_==3)
600  {
601  ROS_DEBUG("Mode 3: Move the actuators using the group velocity controller");
602  for(std::map<std::string,XmlRpc::XmlRpcValue>::iterator p=components_.begin();p!=components_.end();++p)
603  {
604  int count = 0;
605  int component_joint_button_temp = -1;
606  std::string comp_name = p->first;
607  int size = ceil((component_config_[comp_name].joint_velocity.size()+1)/2);
608  for(int i=0; i < size; ++i)
609  {
610  std::ostringstream component_joint_button_stream;
611  component_joint_button_stream << comp_name << "_joint" << i+1 << "_button";
612  std::string component_joint_button = component_joint_button_stream.str();
613  n_.getParam(component_joint_button,component_joint_button_temp);
614  std_msgs::Float64MultiArray vel_cmd;
615  count++;
616  if(!(comp_name.find("left") != std::string::npos) && !(comp_name.find("right") != std::string::npos))
617  {
618  if(component_joint_button_temp>=0 && component_joint_button_temp<(int)joy_msg->buttons.size() && joy_msg->buttons[component_joint_button_temp]==1 && joy_msg->buttons[right_indicator_button_]==0 && joy_msg->buttons[left_indicator_button_]==0)
619  {
620  joy_active_ = true;
621  ROS_INFO("%s velocity mode",comp_name.c_str());
622  vel_cmd.data.resize(component_config_[comp_name].joint_velocity.size());
623  if(up_down_button_>=0 && up_down_button_<(int)joy_msg->axes.size())
624  {
625  vel_cmd.data[count+i-1]=joy_msg->axes[up_down_button_]*component_config_[comp_name].joint_velocity[count+i-1];
626  }
627  if((i+1)*2 <= component_config_[comp_name].joint_velocity.size())
628  {
629  if(right_left_button_>=0 && right_left_button_<(int)joy_msg->axes.size())
630  {
631  vel_cmd.data[count+i]=joy_msg->axes[right_left_button_]*component_config_[comp_name].joint_velocity[count+i];
632  }
633  }
634  component_config_[comp_name].vel_group_controller_publisher_.publish(vel_cmd);
635  }
636  }
637  else if(!(comp_name.find("left") != std::string::npos) && (comp_name.find("right") != std::string::npos))
638  {
639  if(component_joint_button_temp>=0 && component_joint_button_temp<(int)joy_msg->buttons.size() && joy_msg->buttons[component_joint_button_temp]==1 && joy_msg->buttons[right_indicator_button_]==1)
640  {
641  joy_active_ = true;
642  ROS_INFO("%s velocity mode",comp_name.c_str());
643  vel_cmd.data.resize(component_config_[comp_name].joint_velocity.size());
644  if(up_down_button_>=0 && up_down_button_<(int)joy_msg->axes.size())
645  {
646  vel_cmd.data[count+i-1]=joy_msg->axes[up_down_button_]*component_config_[comp_name].joint_velocity[count+i-1];
647  }
648  if((i+1)*2 <= component_config_[comp_name].joint_velocity.size())
649  {
650  if(right_left_button_>=0 && right_left_button_<(int)joy_msg->axes.size())
651  {
652  vel_cmd.data[count+i]=joy_msg->axes[right_left_button_]*component_config_[comp_name].joint_velocity[count+i];
653  }
654  }
655  component_config_[comp_name].vel_group_controller_publisher_.publish(vel_cmd);
656  }
657  }
658  else if((comp_name.find("left") != std::string::npos) && !(comp_name.find("right") != std::string::npos))
659  {
660  if(component_joint_button_temp>=0 && component_joint_button_temp<(int)joy_msg->buttons.size() && joy_msg->buttons[component_joint_button_temp]==1 && joy_msg->buttons[left_indicator_button_]==1)
661  {
662  joy_active_ = true;
663  ROS_INFO("%s velocity mode",comp_name.c_str());
664  vel_cmd.data.resize(component_config_[comp_name].joint_velocity.size());
665  if(up_down_button_>=0 && up_down_button_<(int)joy_msg->axes.size())
666  {
667  vel_cmd.data[count+i-1]=joy_msg->axes[up_down_button_]*component_config_[comp_name].joint_velocity[count+i-1];
668  }
669  if((i+1)*2 <= component_config_[comp_name].joint_velocity.size())
670  {
671  if(right_left_button_>=0 && right_left_button_<(int)joy_msg->axes.size())
672  {
673  vel_cmd.data[count+i]=joy_msg->axes[right_left_button_]*component_config_[comp_name].joint_velocity[count+i];
674  }
675  }
676  component_config_[comp_name].vel_group_controller_publisher_.publish(vel_cmd);
677  }
678  }
679  }
680  }
681  }
682 
683  //-------MODE 4
684  if (mode_==4)
685  {
686  ROS_DEBUG("Mode 4: Move the actuators using the twist controller");
687  for(std::map<std::string,XmlRpc::XmlRpcValue>::iterator p=components_.begin();p!=components_.end();++p)
688  {
689  int component_twist_button_temp = -1;
690  std::string comp_name = p->first;
691  std::string component_twist_button = comp_name + "_twist_button";
692  n_.getParam(component_twist_button,component_twist_button_temp);
693  geometry_msgs::Twist twist_cmd;
694  if (component_twist_button_temp>=0 && component_twist_button_temp<(int)joy_msg->buttons.size() && joy_msg->buttons[component_twist_button_temp]==1)
695  {
696  joy_active_ = true;
697  ROS_INFO("%s twist mode",comp_name.c_str());
698  if(axis_vx_>=0 && axis_vx_<(int)joy_msg->axes.size())
699  twist_cmd.linear.x = joy_msg->axes[axis_vx_]*component_config_[comp_name].twist_max_vel[0]; //*run_factor_;
700  else
701  twist_cmd.linear.x =0.0;
702  if(axis_vy_>=0 && axis_vy_<(int)joy_msg->axes.size())
703  twist_cmd.linear.y = joy_msg->axes[axis_vy_]*component_config_[comp_name].twist_max_vel[1]; //*run_factor_;
704  else
705  twist_cmd.linear.y =0.0;
706  if(axis_vz_>=0 && axis_vz_<(int)joy_msg->axes.size())
707  twist_cmd.linear.z = joy_msg->axes[axis_vz_]*component_config_[comp_name].twist_max_vel[2]; //*run_factor_;
708  else
709  twist_cmd.linear.z =0.0;
710  if(axis_roll_>=0 && axis_roll_<(int)joy_msg->axes.size())
711  twist_cmd.angular.x = joy_msg->axes[axis_roll_]*component_config_[comp_name].twist_max_vel[3]; //*run_factor_;
712  else
713  twist_cmd.angular.x =0.0;
714  if(axis_pitch_>=0 && axis_pitch_<(int)joy_msg->axes.size())
715  twist_cmd.angular.y = joy_msg->axes[axis_pitch_]*component_config_[comp_name].twist_max_vel[4]; //*run_factor_;
716  else
717  twist_cmd.angular.y =0.0;
718  if(axis_yaw_>=0 && axis_yaw_<(int)joy_msg->axes.size())
719  twist_cmd.angular.z = joy_msg->axes[axis_yaw_]*component_config_[comp_name].twist_max_vel[5]; //*run_factor_;
720  else
721  twist_cmd.angular.z =0.0;
722  component_config_[comp_name].twist_controller_publisher_.publish(twist_cmd);
723  }
724  }
725  }
726 }
727 
732 {
733  n_ = ros::NodeHandle("~");
734  if(!n_.hasParam("components"))
735  {
736  ROS_ERROR("parameter components does not exist on ROS Parameter Server, aborting...");
737  exit(0);
738  }
739  // common
740  n_.param("publish_freq",publish_freq_, 30.0);
741  n_.param("run_factor",run_factor_param_,1.5);
742  n_.param("apply_ramp",apply_ramp_,true);
743 
744  // joy config
745  n_.param("joy_num_modes",joy_num_modes_,2);
746  n_.param("mode_switch_button",mode_switch_button_,0);
747  n_.param("joy_config_switch",joy_config_switch_, std::string("D"));
748 
749  // assign axis
750  n_.param("axis_vx",axis_vx_,17);
751  n_.param("axis_vy",axis_vy_,16);
752  n_.param("axis_vz",axis_vz_,17);
753  n_.param("axis_roll",axis_roll_,16);
754  n_.param("axis_pitch",axis_pitch_,19);
755  n_.param("axis_yaw",axis_yaw_,19);
756  n_.param("axis_run",axis_run_,20);
757 
758  // assign buttons
759  n_.param("deadman_button",deadman_button_,11);
760  n_.param("safety_button",safety_button_,10);
761  n_.param("init_button",init_button_,3);
762 
763  n_.param("run_button",run_button_,9);
764  n_.param("dock_button",dock_button_,3);
765  n_.param("undock_button",undock_button_,1);
766 
767  n_.param("right_indicator_button",right_indicator_button_,9);
768  n_.param("left_indicator_button",left_indicator_button_,8);
769  n_.param("up_down_button",up_down_button_,4);
770  n_.param("right_left_button",right_left_button_,5);
771 
772  // output for debugging
773  ROS_DEBUG("init::axis_vx: %d",axis_vx_);
774  ROS_DEBUG("init::axis_vy: %d",axis_vy_);
775  ROS_DEBUG("init::axis_vz: %d",axis_vz_);
776  ROS_DEBUG("init::axis_roll: %d",axis_roll_);
777  ROS_DEBUG("init::axis_pitch: %d",axis_pitch_);
778  ROS_DEBUG("init::axis_yaw: %d",axis_yaw_);
779 
780  ROS_DEBUG("init::deadman_button: %d",deadman_button_);
781  ROS_DEBUG("init::safety_button: %d",safety_button_);
782  ROS_DEBUG("init::init_button: %d",init_button_);
783  ROS_DEBUG("init::run_button: %d",run_button_);
784 
785  ROS_DEBUG("init::right_indicator_button: %d",right_indicator_button_);
786  ROS_DEBUG("init::left_indicator_button: %d",left_indicator_button_);
787  ROS_DEBUG("init::up_down_button: %d",up_down_button_);
788  ROS_DEBUG("init::right_left_button: %d",right_left_button_);
789 
790  joy_sub_ = n_.subscribe("/joy",1,&CobTeleop::joy_cb,this);
791  mode_ = 1;
793  joy_active_ = false;
794  safe_mode_ = true;
795  axis_run_updated_ = false;
796 
797  cob_light::LightMode light;
798  light.mode = cob_light::LightModes::FLASH;
799  light.frequency = 5;
800  light.priority = 12;
801  std_msgs::ColorRGBA color;
802  color.r = 0;
803  color.g = 1;
804  color.b = 0;
805  color.a = 1;
806  light.pulses = 2;
807  light.colors.push_back(color);
808  confirm_light_goal_.mode = light;
809 
810  color.r = 1;
811  color.g = 0;
812  light.pulses = 3;
813  light.colors.clear();
814  light.colors.push_back(color);
815  error_light_goal_.mode = light;
816 }
817 
818 
819 int main(int argc, char** argv)
820 {
821  ros::init(argc, argv, "cob_teleop");
822  CobTeleop cob_teleop;
823  cob_teleop.init();
824  cob_teleop.getConfigurationFromParameters();
825  ros::Rate loop_rate(cob_teleop.publish_freq_); //Hz
826  while(cob_teleop.n_.ok())
827  {
828  cob_teleop.updateBase();
829  ros::spinOnce();
830  loop_rate.sleep();
831  }
832 
833  exit(0);
834  return(0);
835 }
XmlRpc::XmlRpcValue::size
int size() const
CobTeleop::joy_config_switch_
std::string joy_config_switch_
Definition: cob_teleop.cpp:84
CobTeleop::undock_button_
int undock_button_
Definition: cob_teleop.cpp:64
CobTeleop::dock_client_
DockClient_ * dock_client_
Definition: cob_teleop.cpp:108
CobTeleop::DockClient_
actionlib::SimpleActionClient< cob_actions::SetStringAction > DockClient_
Definition: cob_teleop.cpp:107
CobTeleop::updateBase
void updateBase()
Definition: cob_teleop.cpp:314
CobTeleop::led_mode_
XmlRpc::XmlRpcValue led_mode_
Definition: cob_teleop.cpp:86
ros::Publisher
CobTeleop::component_config::twist_safety_controller_publisher_
ros::Publisher twist_safety_controller_publisher_
Definition: cob_teleop.cpp:51
CobTeleop::component_config::sss_default_target
std::string sss_default_target
Definition: cob_teleop.cpp:45
color
CobTeleop::safety_button_
int safety_button_
Definition: cob_teleop.cpp:75
CobTeleop::axis_vx_
int axis_vx_
Definition: cob_teleop.cpp:57
CobTeleop::axis_pitch_
int axis_pitch_
Definition: cob_teleop.cpp:57
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
CobTeleop::joy_active_
bool joy_active_
Definition: cob_teleop.cpp:77
CobTeleop::axis_run_
int axis_run_
Definition: cob_teleop.cpp:57
CobTeleop::up_down_button_
int up_down_button_
Definition: cob_teleop.cpp:69
CobTeleop::mode_
int mode_
Definition: cob_teleop.cpp:83
CobTeleop
Definition: cob_teleop.cpp:35
CobTeleop::joy_cb
void joy_cb(const sensor_msgs::Joy::ConstPtr &joy_msg)
Definition: cob_teleop.cpp:407
s
XmlRpcServer s
CobTeleop::error_light_goal_
cob_light::SetLightModeGoal error_light_goal_
Definition: cob_teleop.cpp:116
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
CobTeleop::axis_roll_
int axis_roll_
Definition: cob_teleop.cpp:57
actionlib::SimpleActionClient::waitForServer
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
CobTeleop::left_indicator_button_
int left_indicator_button_
Definition: cob_teleop.cpp:68
CobTeleop::setLight
void setLight(int mode)
Definition: cob_teleop.cpp:386
CobTeleop::axis_yaw_
int axis_yaw_
Definition: cob_teleop.cpp:57
actionlib::SimpleClientGoalState
ros::spinOnce
ROSCPP_DECL void spinOnce()
CobTeleop::component_config::joint_velocity
std::vector< double > joint_velocity
Definition: cob_teleop.cpp:46
CobTeleop::LEDS_
XmlRpc::XmlRpcValue LEDS_
Definition: cob_teleop.cpp:85
CobTeleop::right_left_button_
int right_left_button_
Definition: cob_teleop.cpp:70
CobTeleop::script_goal_
cob_script_server::ScriptGoal script_goal_
Definition: cob_teleop.cpp:95
mode
bool mode
Definition: keyboard_publisher.cpp:84
CobTeleop::run_factor_
double run_factor_
Definition: cob_teleop.cpp:80
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
CobTeleop::enable_sound_
bool enable_sound_
Definition: cob_teleop.cpp:99
CobTeleop::run_factor_param_
double run_factor_param_
Definition: cob_teleop.cpp:80
CobTeleop::undock_action_name_
std::string undock_action_name_
Definition: cob_teleop.cpp:113
CobTeleop::component_config
Definition: cob_teleop.cpp:39
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
CobTeleop::component_config_
std::map< std::string, component_config > component_config_
Definition: cob_teleop.cpp:54
CobTeleop::safe_mode_
bool safe_mode_
Definition: cob_teleop.cpp:78
XmlRpc::XmlRpcValue::TypeStruct
TypeStruct
CobTeleop::say
void say(std::string text, bool blocking)
Definition: cob_teleop.cpp:372
actionlib::SimpleActionClient
CobTeleop::publish_freq_
double publish_freq_
Definition: cob_teleop.cpp:79
CobTeleop::enable_light_
bool enable_light_
Definition: cob_teleop.cpp:104
XmlRpc::XmlRpcValue::TypeDouble
TypeDouble
actionlib::SimpleClientGoalState::getText
std::string getText() const
CobTeleop::undock_client_
UndockClient_ * undock_client_
Definition: cob_teleop.cpp:112
CobTeleop::mode_switch_button_
int mode_switch_button_
Definition: cob_teleop.cpp:82
actionlib::SimpleClientGoalState::PENDING
PENDING
simple_action_client.h
CobTeleop::vel_req_
std::vector< double > vel_req_
Definition: cob_teleop.cpp:119
ROS_DEBUG
#define ROS_DEBUG(...)
CobTeleop::component_config::twist_max_vel
std::vector< double > twist_max_vel
Definition: cob_teleop.cpp:47
CobTeleop::sss_client_
ScriptClient_ * sss_client_
Definition: cob_teleop.cpp:94
CobTeleop::sound_action_name_
std::string sound_action_name_
Definition: cob_teleop.cpp:100
CobTeleop::dock_action_name_
std::string dock_action_name_
Definition: cob_teleop.cpp:109
actionlib::SimpleActionClient::sendGoal
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
actionlib::SimpleActionClient::getResult
ResultConstPtr getResult() const
CobTeleop::component_config::twist_controller_publisher_
ros::Publisher twist_controller_publisher_
Definition: cob_teleop.cpp:50
XmlRpc::XmlRpcValue::TypeString
TypeString
CobTeleop::SayClient_
actionlib::SimpleActionClient< cob_sound::SayAction > SayClient_
Definition: cob_teleop.cpp:97
CobTeleop::right_indicator_button_
int right_indicator_button_
Definition: cob_teleop.cpp:67
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
ROS_WARN
#define ROS_WARN(...)
XmlRpcValue.h
CobTeleop::component_config::twist_safety_topic_name
std::string twist_safety_topic_name
Definition: cob_teleop.cpp:43
CobTeleop::vel_base_
std::vector< double > vel_base_
Definition: cob_teleop.cpp:120
main
int main(int argc, char **argv)
Definition: cob_teleop.cpp:819
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
actionlib::SimpleActionClient::waitForResult
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
CobTeleop::switch_mode
sensor_msgs::JoyFeedbackArray switch_mode()
Definition: cob_teleop.cpp:267
XmlRpc::XmlRpcValue::end
iterator end()
ros::Rate::sleep
bool sleep()
XmlRpc::XmlRpcValue::getType
const Type & getType() const
CobTeleop::setlight_client_
SetLightClient_ * setlight_client_
Definition: cob_teleop.cpp:103
XmlRpc::XmlRpcValue::TypeArray
TypeArray
ros::NodeHandle::ok
bool ok() const
CobTeleop::vel_old_
std::vector< double > vel_old_
Definition: cob_teleop.cpp:118
CobTeleop::component_config::vel_group_topic_name
std::string vel_group_topic_name
Definition: cob_teleop.cpp:44
CobTeleop::ScriptClient_
actionlib::SimpleActionClient< cob_script_server::ScriptAction > ScriptClient_
Definition: cob_teleop.cpp:93
CobTeleop::joy_sub_
ros::Subscriber joy_sub_
Definition: cob_teleop.cpp:90
CobTeleop::axis_vz_
int axis_vz_
Definition: cob_teleop.cpp:57
CobTeleop::SetLightClient_
actionlib::SimpleActionClient< cob_light::SetLightModeAction > SetLightClient_
Definition: cob_teleop.cpp:102
CobTeleop::UndockClient_
actionlib::SimpleActionClient< cob_actions::SetStringAction > UndockClient_
Definition: cob_teleop.cpp:111
actionlib::SimpleClientGoalState::ACTIVE
ACTIVE
CobTeleop::getConfigurationFromParameters
void getConfigurationFromParameters()
Definition: cob_teleop.cpp:132
CobTeleop::joy_num_modes_
int joy_num_modes_
Definition: cob_teleop.cpp:81
CobTeleop::components_
XmlRpc::XmlRpcValue components_
Definition: cob_teleop.cpp:88
ROS_ERROR
#define ROS_ERROR(...)
CobTeleop::n_
ros::NodeHandle n_
Definition: cob_teleop.cpp:89
CobTeleop::light_action_name_
std::string light_action_name_
Definition: cob_teleop.cpp:105
CobTeleop::init_button_
int init_button_
Definition: cob_teleop.cpp:76
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
CobTeleop::axis_run_updated_
bool axis_run_updated_
Definition: cob_teleop.cpp:58
CobTeleop::apply_ramp_
bool apply_ramp_
Definition: cob_teleop.cpp:121
CobTeleop::deadman_button_
int deadman_button_
Definition: cob_teleop.cpp:74
CobTeleop::component_config::twist_max_acc
std::vector< double > twist_max_acc
Definition: cob_teleop.cpp:48
CobTeleop::say_client_
SayClient_ * say_client_
Definition: cob_teleop.cpp:98
ros::Rate
actionlib::SimpleActionClient::getState
SimpleClientGoalState getState() const
XmlRpc::XmlRpcValue::begin
iterator begin()
CobTeleop::component_config::twist_topic_name
std::string twist_topic_name
Definition: cob_teleop.cpp:42
CobTeleop::component_config::vel_group_controller_publisher_
ros::Publisher vel_group_controller_publisher_
Definition: cob_teleop.cpp:49
CobTeleop::run_button_
int run_button_
Definition: cob_teleop.cpp:62
ROS_INFO
#define ROS_INFO(...)
ROS_ASSERT
#define ROS_ASSERT(cond)
ros::Duration
CobTeleop::joint_states_sub_
ros::Subscriber joint_states_sub_
Definition: cob_teleop.cpp:91
CobTeleop::init
void init()
Initializes node to get parameters, subscribe to topics.
Definition: cob_teleop.cpp:731
CobTeleop::confirm_light_goal_
cob_light::SetLightModeGoal confirm_light_goal_
Definition: cob_teleop.cpp:115
CobTeleop::dock_button_
int dock_button_
Definition: cob_teleop.cpp:63
CobTeleop::axis_vy_
int axis_vy_
Definition: cob_teleop.cpp:57
XmlRpc::XmlRpcValue
CobTeleop::component_config::key
std::string key
Definition: cob_teleop.cpp:41
ros::NodeHandle
ros::Subscriber


cob_teleop
Author(s): Florian Weisshardt, Maximilian Sieber
autogenerated on Fri Aug 2 2024 09:45:55