00001
00064 #include <cstdlib>
00065 #include <cstdio>
00066 #include <unistd.h>
00067 #include <XmlRpcValue.h>
00068 #include <ros/ros.h>
00069 #include <joy/Joy.h>
00070 #include <sensor_msgs/JointState.h>
00071 #include <trajectory_msgs/JointTrajectory.h>
00072 #include <geometry_msgs/Twist.h>
00073
00074 #include <cob_srvs/Trigger.h>
00075 #include <brics_actuator/JointPositions.h>
00076 #include <brics_actuator/JointVelocities.h>
00077
00078 const int PUBLISH_FREQ = 20.0;
00079
00085 class TeleopCOB
00086 {
00087 public:
00088 struct joint_module{
00089 std::string key;
00090 std::vector<std::string> joint_names;
00091 std::vector<double> req_joint_pos_;
00092 std::vector<double> req_joint_vel_;
00093 std::vector<double> steps;
00094 ros::Publisher module_publisher_;
00095 ros::Publisher module_publisher_brics_;
00096 };
00097
00098 std::map<std::string,joint_module> joint_modules_;
00099
00100 struct base_module_struct{
00101 std::vector<double> req_vel_;
00102 std::vector<double> vel_old_;
00103 std::vector<double> max_vel_;
00104 std::vector<double> max_acc_;
00105 ros::Publisher base_publisher_;
00106 } base_module_;
00107
00108 bool has_base_module_;
00109
00110 int lower_neck_button_,upper_neck_button_;
00111 int tray_button_;
00112 int axis_vx_,axis_vy_,axis_vth_;
00113 int arm_joint12_button_;
00114 int arm_joint34_button_;
00115 int arm_joint56_button_;
00116 int arm_joint7_button_;
00117
00118 int up_down_, left_right_;
00119
00120
00121 int deadman_button_, run_button_, stop_base_button_, recover_base_button_;
00122 bool joy_active_, stopped_;
00123 double run_factor_, run_factor_param_;
00124
00125
00126 ros::NodeHandle n_;
00127 ros::Subscriber joy_sub_;
00128 ros::Subscriber joint_states_sub_;
00129
00130 bool got_init_values_;
00131 double time_for_init_;
00132
00133 struct combined_joints_struct{
00134 std::vector<std::string> joint_names_;
00135 std::vector<double> joint_init_values_;
00136 std::vector<joint_module*> module_ref_;
00137 }combined_joints_;
00138 std::vector<std::string> joint_names_;
00139 std::vector<double> joint_init_values_;
00140
00141 TeleopCOB();
00142 void waitForParameters();
00143 void getConfigurationFromParameters();
00144 void init();
00145 void joy_cb(const joy::Joy::ConstPtr &joy_msg);
00146 void joint_states_cb(const sensor_msgs::JointState::ConstPtr &joint_states_msg);
00147 void update();
00148 void update_joint_modules();
00149 void update_base();
00150 void setInitValues();
00151 ~TeleopCOB();
00152
00153 private:
00154 bool assign_joint_module(std::string,XmlRpc::XmlRpcValue);
00155 bool assign_base_module(XmlRpc::XmlRpcValue);
00156 };
00157
00158 void TeleopCOB::waitForParameters()
00159 {
00160 while(!n_.hasParam("/robot_config/robot_modules"))
00161 {
00162 sleep(1);
00163 ROS_WARN("no robot_module list loaded");
00164 }
00165
00166
00167 XmlRpc::XmlRpcValue module_list;
00168 n_.getParam("/robot_config/robot_modules",module_list);
00169 ROS_ASSERT(module_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00170
00171 for(int i=0;i<module_list.size();i++)
00172 {
00173 ROS_ASSERT(module_list[i].getType() == XmlRpc::XmlRpcValue::TypeString);
00174 std::string s((std::string)module_list[i]);
00175 ROS_DEBUG("searching for module = %s", s.c_str());
00176
00177
00178 while(!n_.hasParam("modules/"+s))
00179 {
00180 sleep(1);
00181 ROS_WARN("required module not loaded");
00182 }
00183 }
00184
00185 ROS_DEBUG("module list found");
00186 }
00187
00188 void TeleopCOB::getConfigurationFromParameters()
00189 {
00190
00191 if(n_.hasParam("modules"))
00192 {
00193 XmlRpc::XmlRpcValue modules;
00194 ROS_DEBUG("modules found ");
00195 n_.getParam("modules", modules);
00196 if(modules.getType() == XmlRpc::XmlRpcValue::TypeStruct)
00197 {
00198 ROS_DEBUG("modules are of type struct with size %d",(int)modules.size());
00199
00200 for(std::map<std::string,XmlRpc::XmlRpcValue>::iterator p=modules.begin();p!=modules.end();++p)
00201 {
00202 std::string mod_name = p->first;
00203 ROS_DEBUG("module name: %s",mod_name.c_str());
00204 XmlRpc::XmlRpcValue mod_struct = p->second;
00205 if(mod_struct.getType() != XmlRpc::XmlRpcValue::TypeStruct)
00206 ROS_WARN("invalid module, name: %s",mod_name.c_str());
00207
00208
00209
00210
00211 if(!assign_joint_module(mod_name, mod_struct))
00212 {
00213
00214 ROS_DEBUG("wheel module found");
00215 assign_base_module(mod_struct);
00216 }
00217 }
00218 }
00219 }
00220 }
00221
00233 bool TeleopCOB::assign_joint_module(std::string mod_name, XmlRpc::XmlRpcValue mod_struct)
00234 {
00235
00236
00237
00238
00239 bool is_joint_module = false;
00240 joint_module tempModule;
00241 for(std::map<std::string,XmlRpc::XmlRpcValue>::iterator ps=mod_struct.begin();ps!=mod_struct.end();++ps)
00242 {
00243 std::string par_name = ps->first;
00244 ROS_DEBUG("par name: %s",par_name.c_str());
00245
00246 if(par_name.compare("joint_names")==0)
00247 {
00248 ROS_DEBUG("joint names found");
00249 XmlRpc::XmlRpcValue joint_names = ps->second;
00250
00251 ROS_ASSERT(joint_names.getType() == XmlRpc::XmlRpcValue::TypeArray);
00252 ROS_DEBUG("joint_names.size: %d \n", joint_names.size());
00253 for(int i=0;i<joint_names.size();i++)
00254 {
00255 ROS_ASSERT(joint_names[i].getType() == XmlRpc::XmlRpcValue::TypeString);
00256 std::string s((std::string)joint_names[i]);
00257 ROS_DEBUG("joint_name found = %s",s.c_str());
00258 tempModule.joint_names.push_back(s);
00259 }
00260
00261 tempModule.req_joint_pos_.resize(joint_names.size());
00262 tempModule.req_joint_vel_.resize(joint_names.size());
00263
00264 is_joint_module = true;
00265
00266 }else if(par_name.compare("joint_step")==0){
00267 ROS_DEBUG("joint steps found");
00268 XmlRpc::XmlRpcValue joint_steps = ps->second;
00269
00270 ROS_ASSERT(joint_steps.getType() == XmlRpc::XmlRpcValue::TypeArray);
00271 ROS_DEBUG("joint_steps.size: %d \n", joint_steps.size());
00272 for(int i=0;i<joint_steps.size();i++)
00273 {
00274 ROS_ASSERT(joint_steps[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00275 double step((double)joint_steps[i]);
00276 ROS_DEBUG("joint_step found = %f",step);
00277 tempModule.steps.push_back(step);
00278 }
00279 }
00280 }
00281 if(is_joint_module)
00282 {
00283
00284 tempModule.module_publisher_ = n_.advertise<trajectory_msgs::JointTrajectory>(("/"+mod_name+"_controller/command"),1);
00285 tempModule.module_publisher_brics_ = n_.advertise<brics_actuator::JointVelocities>(("/"+mod_name+"_controller/command_vel"),1);
00286
00287 ROS_DEBUG("head module stored");
00288 joint_modules_.insert(std::pair<std::string,joint_module>(mod_name,tempModule));
00289 }
00290 return is_joint_module;
00291 }
00303 bool TeleopCOB::assign_base_module(XmlRpc::XmlRpcValue mod_struct)
00304 {
00305 for(std::map<std::string,XmlRpc::XmlRpcValue>::iterator ps=mod_struct.begin();ps!=mod_struct.end();++ps)
00306 {
00307 std::string par_name = ps->first;
00308 ROS_DEBUG("par name: %s",par_name.c_str());
00309
00310 if(par_name.compare("max_velocity")==0)
00311 {
00312 ROS_DEBUG("max vel found");
00313 XmlRpc::XmlRpcValue max_vel = ps->second;
00314
00315 ROS_ASSERT(max_vel.getType() == XmlRpc::XmlRpcValue::TypeArray);
00316 if(max_vel.size()!=3){ROS_WARN("invalid base parameter size");}
00317 ROS_DEBUG("max_vel.size: %d \n", max_vel.size());
00318 for(int i=0;i<max_vel.size();i++)
00319 {
00320 ROS_ASSERT(max_vel[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00321 double val = (double)max_vel[i];
00322 ROS_DEBUG("max vel value = %f",val);
00323 base_module_.max_vel_.push_back(val);
00324 }
00325 }
00326 else if(par_name.compare("max_acceleration")==0)
00327 {
00328 ROS_DEBUG("max acc found");
00329 XmlRpc::XmlRpcValue max_acc = ps->second;
00330
00331 ROS_ASSERT(max_acc.getType() == XmlRpc::XmlRpcValue::TypeArray);
00332 if(max_acc.size()!=3){ROS_DEBUG("invalid base parameter size");}
00333 ROS_DEBUG("max_acc.size: %d \n", max_acc.size());
00334 for(int i=0;i<max_acc.size();i++)
00335 {
00336 ROS_ASSERT(max_acc[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00337 double val = (double)max_acc[i];
00338 ROS_DEBUG("max acc value = %f", val);
00339 base_module_.max_acc_.push_back(val);
00340 }
00341 }
00342 else
00343 {
00344 ROS_WARN("unsupported base module parameter read");
00345 }
00346 }
00347
00348
00349
00350 base_module_.req_vel_.resize(base_module_.max_acc_.size());
00351 base_module_.vel_old_.resize(base_module_.max_acc_.size());
00352 base_module_.base_publisher_ = n_.advertise<geometry_msgs::Twist>("/base_controller/command",1);
00353 ROS_DEBUG("base module stored");
00354 has_base_module_ = true;
00355 return true;
00356 }
00357
00361 TeleopCOB::TeleopCOB()
00362 {
00363 waitForParameters();
00364 getConfigurationFromParameters();
00365 got_init_values_ = false;
00366 time_for_init_ = 0.0;
00367 joy_active_ = false;
00368 run_factor_ = 1.0;
00369
00370
00371 for(std::map<std::string,joint_module>::iterator module_it=joint_modules_.begin();module_it!=joint_modules_.end();++module_it){
00372 std::vector<std::string> names = (module_it->second).joint_names;
00373 for(int i=0; i<names.size();i++){
00374 joint_names_.push_back(names[i]);
00375 combined_joints_.joint_names_.push_back(names[i]);
00376 combined_joints_.joint_init_values_.push_back(0.0);
00377 combined_joints_.module_ref_.push_back((joint_module*)(&(module_it->second)));
00378 }
00379 }
00380 joint_init_values_.resize(joint_names_.size());
00381 }
00382
00386 TeleopCOB::~TeleopCOB()
00387 {
00388 }
00389
00393 void TeleopCOB::init()
00394 {
00395
00396 n_.param("run_factor",run_factor_param_,1.5);
00397
00398
00399 n_.param("lower_neck_button",lower_neck_button_,6);
00400 n_.param("upper_neck_button",upper_neck_button_,4);
00401 n_.param("tray_button",tray_button_,3);
00402 n_.param("arm_joint12_button",arm_joint12_button_,0);
00403 n_.param("arm_joint34_button",arm_joint34_button_,1);
00404 n_.param("arm_joint56_button",arm_joint56_button_,2);
00405 n_.param("arm_joint7_button",arm_joint7_button_,3);
00406 n_.param("deadman_button",deadman_button_,5);
00407 n_.param("run_button",run_button_,7);
00408 n_.param("stop_base_button",stop_base_button_,8);
00409 n_.param("recover_base_button",recover_base_button_,9);
00410
00411
00412 n_.param("axis_vx",axis_vx_,1);
00413 n_.param("axis_vy",axis_vy_,0);
00414 n_.param("axis_vth",axis_vth_,2);
00415 n_.param("up_down",up_down_,5);
00416 n_.param("left_right",left_right_,4);
00417
00418
00419 ROS_DEBUG("init::lower_neck_button: %d",lower_neck_button_);
00420 ROS_DEBUG("init::upper_neck_button: %d",upper_neck_button_);
00421 ROS_DEBUG("init::tray_button: %d",tray_button_);
00422 ROS_DEBUG("init::arm_joint12_button: %d",arm_joint12_button_);
00423 ROS_DEBUG("init::arm_joint34_button: %d",arm_joint34_button_);
00424 ROS_DEBUG("init::arm_joint56_button: %d",arm_joint56_button_);
00425 ROS_DEBUG("init::arm_joint7_button: %d",arm_joint7_button_);
00426 ROS_DEBUG("init::deadman_button: %d",deadman_button_);
00427 ROS_DEBUG("init::run_button: %d",run_button_);
00428 ROS_DEBUG("init::stop_base_button: %d",stop_base_button_);
00429 ROS_DEBUG("init::recover_base_button: %d",recover_base_button_);
00430
00431 ROS_DEBUG("init::axis_vx: %d",axis_vx_);
00432 ROS_DEBUG("init::axis_vy: %d",axis_vy_);
00433 ROS_DEBUG("init::axis_vth: %d",axis_vth_);
00434 ROS_DEBUG("init::up_down: %d",up_down_);
00435 ROS_DEBUG("init::left_right: %d",left_right_);
00436
00437
00438 joy_sub_ = n_.subscribe("/joy",1,&TeleopCOB::joy_cb,this);
00439 joint_states_sub_ = n_.subscribe("/joint_states",1,&TeleopCOB::joint_states_cb,this);
00440 }
00441
00445 void TeleopCOB::setInitValues()
00446 {
00447
00448
00449 for(int i=0; i<combined_joints_.joint_init_values_.size();i++){
00450
00451
00452
00453 for(int j=0; j<combined_joints_.module_ref_[i]->joint_names.size();j++){
00454
00455 if(combined_joints_.module_ref_[i]->joint_names[j].compare(combined_joints_.joint_names_[i])==0){
00456 combined_joints_.module_ref_[i]->req_joint_pos_[j] = combined_joints_.joint_init_values_[i];
00457 combined_joints_.module_ref_[i]->req_joint_vel_[j] = 0.0;
00458 break;
00459 }
00460 }
00461 }
00462
00463
00464
00465 got_init_values_ = true;
00466 }
00467
00475 void TeleopCOB::joint_states_cb(const sensor_msgs::JointState::ConstPtr &joint_states_msg)
00476 {
00477 if (!got_init_values_ && stopped_ && joy_active_)
00478 {
00479 ROS_DEBUG("joint_states_cb: getting init values");
00480 for (int j = 0; j<joint_names_.size(); j++ )
00481 {
00482 for (int i = 0; i<joint_states_msg->name.size(); i++ )
00483 {
00484 ROS_DEBUG("joint names in init: %s should match %s",joint_names_[j].c_str(),joint_states_msg->name[i].c_str());
00485 if (joint_states_msg->name[i] == joint_names_[j])
00486 {
00487 joint_init_values_[j] = joint_states_msg->position[i];
00488 if(joint_names_[j]!=combined_joints_.joint_names_[j])
00489 ROS_ERROR("error in new joint name collection, name miss match.");
00490 combined_joints_.joint_init_values_[j] = joint_states_msg->position[i];
00491 ROS_DEBUG("joint %s found. init value = %f",joint_names_[j].c_str(),joint_init_values_[j]);
00492 break;
00493 }
00494 }
00495 }
00496 setInitValues();
00497 }
00498 }
00499
00507 void TeleopCOB::joy_cb(const joy::Joy::ConstPtr &joy_msg)
00508 {
00509
00510 if(deadman_button_>=0 && deadman_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[deadman_button_]==1)
00511 {
00512 if (!joy_active_)
00513 {
00514 ROS_INFO("joystick is active");
00515 joy_active_ = true;
00516 got_init_values_ = false;
00517 }
00518 }
00519 else
00520 {
00521 ROS_DEBUG("joystick is not active");
00522 joy_active_ = false;
00523 return;
00524 }
00525
00526
00527 if(run_button_>=0 && run_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[run_button_]==1)
00528 {
00529 run_factor_ = run_factor_param_;
00530 }
00531 else
00532 {
00533 run_factor_ = 1.0;
00534 }
00535
00536
00537 if(recover_base_button_>=0 && recover_base_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[recover_base_button_]==1)
00538 {
00539 ros::ServiceClient client_init_base = n_.serviceClient<cob_srvs::Trigger>("/base_controller/init");
00540
00541 ROS_INFO("Init base");
00542 cob_srvs::Trigger srv = cob_srvs::Trigger();
00543 if (client_init_base.call(srv))
00544 {
00545 ROS_INFO("Base init successfully");
00546 }
00547 else
00548 {
00549 ROS_ERROR("Failed to call service /base_controller/init");
00550 }
00551
00552 ros::ServiceClient client_recover_base = n_.serviceClient<cob_srvs::Trigger>("/base_controller/recover");
00553
00554 ROS_INFO("Recover base");
00555 if (client_recover_base.call(srv))
00556 {
00557 ROS_INFO("Base recovered successfully");
00558 }
00559 else
00560 {
00561 ROS_ERROR("Failed to call service /base_controller/recover");
00562 }
00563 }
00564
00565
00566 if(stop_base_button_>=0 && stop_base_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[stop_base_button_]==1)
00567 {
00568 ros::ServiceClient client_stop_base = n_.serviceClient<cob_srvs::Trigger>("/base_controller/stop");
00569
00570 ROS_INFO("Stop base");
00571 cob_srvs::Trigger srv = cob_srvs::Trigger();
00572 if (client_stop_base.call(srv))
00573 {
00574 ROS_INFO("Base stop successfully");
00575 }
00576 else
00577 {
00578 ROS_ERROR("Failed to call service /base_controller/stop");
00579 }
00580 }
00581
00582
00583
00584
00585 if(joint_modules_.find("head")!=joint_modules_.end())
00586 {
00587 if(upper_neck_button_>=0 &&
00588 upper_neck_button_<(int)joy_msg->buttons.size() &&
00589 joy_msg->buttons[upper_neck_button_]==1)
00590 {
00591
00592 if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]<0.0)
00593 joint_modules_["head"].req_joint_vel_[0] = (int)joy_msg->buttons[upper_neck_button_]*joint_modules_["head"].steps[0]*run_factor_;
00594 else if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]>0.0)
00595 joint_modules_["head"].req_joint_vel_[0] = -1*(int)joy_msg->buttons[upper_neck_button_]*joint_modules_["head"].steps[0]*run_factor_;
00596 else
00597 joint_modules_["head"].req_joint_vel_[0]= 0.0;
00598 ROS_DEBUG("cb::upper neck pan velocity: %f",joint_modules_["head"].req_joint_vel_[0]);
00599
00600
00601 if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]>0.0)
00602 joint_modules_["head"].req_joint_vel_[1] = -1*(int)joy_msg->buttons[upper_neck_button_]*joint_modules_["head"].steps[1]*run_factor_;
00603 else if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]<0.0)
00604 joint_modules_["head"].req_joint_vel_[1] = (int)joy_msg->buttons[upper_neck_button_]*joint_modules_["head"].steps[1]*run_factor_;
00605 else
00606 joint_modules_["head"].req_joint_vel_[1] = 0.0;
00607 ROS_DEBUG("cb::upper neck tilt velocity: %f",joint_modules_["head"].req_joint_vel_[1]);
00608
00609 }
00610 else
00611 {
00612 joint_modules_["head"].req_joint_vel_[0] = 0.0;
00613 joint_modules_["head"].req_joint_vel_[1] = 0.0;
00614 }
00615 }
00616 if(joint_modules_.find("torso")!=joint_modules_.end())
00617 {
00618
00619
00620 if(lower_neck_button_>=0 &&
00621 lower_neck_button_<(int)joy_msg->buttons.size() &&
00622 joy_msg->buttons[lower_neck_button_]==1)
00623 {
00624
00625 if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]<0.0)
00626 joint_modules_["torso"].req_joint_vel_[0] = (int)joy_msg->buttons[lower_neck_button_]*joint_modules_["torso"].steps[0]*run_factor_;
00627 else if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]>0.0)
00628 joint_modules_["torso"].req_joint_vel_[0] = -1*(int)joy_msg->buttons[lower_neck_button_]*joint_modules_["torso"].steps[0]*run_factor_;
00629 else
00630 joint_modules_["torso"].req_joint_vel_[0] = 0.0;
00631 ROS_DEBUG("cb::lower neck pan velocity: %f",joint_modules_["torso"].req_joint_vel_[0]);
00632
00633
00634 if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]>0.0)
00635 joint_modules_["torso"].req_joint_vel_[1] = (int)joy_msg->buttons[lower_neck_button_]*joint_modules_["torso"].steps[1]*run_factor_;
00636 else if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]<0.0)
00637 joint_modules_["torso"].req_joint_vel_[1] = -1*(int)joy_msg->buttons[lower_neck_button_]*joint_modules_["torso"].steps[1]*run_factor_;
00638 else
00639 joint_modules_["torso"].req_joint_vel_[1] = 0.0;
00640 ROS_DEBUG("cb::lower neck tilt velocity: %f",joint_modules_["torso"].req_joint_vel_[1]);
00641 }
00642 else
00643 {
00644 joint_modules_["torso"].req_joint_vel_[0] = 0.0;
00645 joint_modules_["torso"].req_joint_vel_[1] = 0.0;
00646 }
00647
00648
00649 if(upper_neck_button_>=0 &&
00650 upper_neck_button_<(int)joy_msg->buttons.size() &&
00651 joy_msg->buttons[upper_neck_button_]==1)
00652 {
00653
00654 if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]<0.0)
00655 joint_modules_["torso"].req_joint_vel_[2] = (int)joy_msg->buttons[upper_neck_button_]*joint_modules_["torso"].steps[2]*run_factor_;
00656 else if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]>0.0)
00657 joint_modules_["torso"].req_joint_vel_[2] = -1*(int)joy_msg->buttons[upper_neck_button_]*joint_modules_["torso"].steps[2]*run_factor_;
00658 else
00659 joint_modules_["torso"].req_joint_vel_[2] = 0.0;
00660 ROS_DEBUG("cb::upper neck pan velocity: %f",joint_modules_["torso"].req_joint_vel_[2]);
00661
00662
00663 if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]>0.0)
00664 joint_modules_["torso"].req_joint_vel_[3] = (int)joy_msg->buttons[upper_neck_button_]*joint_modules_["torso"].steps[3]*run_factor_;
00665 else if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]<0.0)
00666 joint_modules_["torso"].req_joint_vel_[3] = -1*(int)joy_msg->buttons[upper_neck_button_]*joint_modules_["torso"].steps[3]*run_factor_;
00667 else
00668 joint_modules_["torso"].req_joint_vel_[3] = 0.0;
00669 ROS_DEBUG("cb::upper neck tilt velocity: %f",joint_modules_["torso"].req_joint_vel_[3]);
00670 }
00671 else
00672 {
00673 joint_modules_["torso"].req_joint_vel_[2] = 0.0;
00674 joint_modules_["torso"].req_joint_vel_[3] = 0.0;
00675 }
00676 }
00677
00678 if(joint_modules_.find("tray")!=joint_modules_.end())
00679 {
00680
00681 if(tray_button_>=0 && tray_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[tray_button_]==1)
00682 {
00683 if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]>0.0)
00684 joint_modules_["tray"].req_joint_vel_[0] = (int)joy_msg->buttons[tray_button_]*joint_modules_["tray"].steps[0]*run_factor_;
00685 else if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]<0.0)
00686 joint_modules_["tray"].req_joint_vel_[0] = -1*(int)joy_msg->buttons[tray_button_]*joint_modules_["tray"].steps[0]*run_factor_;
00687 else
00688 joint_modules_["tray"].req_joint_vel_[0] = 0.0;
00689 ROS_DEBUG("cb::tray velocity: %f",joint_modules_["tray"].req_joint_vel_[0]);
00690 }
00691 else
00692 {
00693 joint_modules_["tray"].req_joint_vel_[0] = 0.0;
00694 }
00695 }
00696 if(joint_modules_.find("arm")!=joint_modules_.end())
00697 {
00698
00699
00700
00701
00702 if(joint_modules_["arm"].req_joint_vel_.size()>1 && arm_joint12_button_>=0 && arm_joint12_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[arm_joint12_button_]==1)
00703 {
00704
00705 if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]<0.0)
00706 joint_modules_["arm"].req_joint_vel_[0] = -1*(int)joy_msg->buttons[arm_joint12_button_]*joint_modules_["arm"].steps[0]*run_factor_;
00707 else if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]>0.0)
00708 joint_modules_["arm"].req_joint_vel_[0] = (int)joy_msg->buttons[arm_joint12_button_]*joint_modules_["arm"].steps[0]*run_factor_;
00709 else
00710 joint_modules_["arm"].req_joint_vel_[0] = 0.0;
00711 ROS_DEBUG("cb::arm joint1 velocity: %f",joint_modules_["arm"].req_joint_vel_[0]);
00712
00713
00714 if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]>0.0)
00715 joint_modules_["arm"].req_joint_vel_[1] = (int)joy_msg->buttons[arm_joint12_button_]*joint_modules_["arm"].steps[1]*run_factor_;
00716 else if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]<0.0)
00717 joint_modules_["arm"].req_joint_vel_[1] = -1*(int)joy_msg->buttons[arm_joint12_button_]*joint_modules_["arm"].steps[1]*run_factor_;
00718 else
00719 joint_modules_["arm"].req_joint_vel_[1] = 0.0;
00720 ROS_DEBUG("cb::arm joint2 velocity: %f",joint_modules_["arm"].req_joint_vel_[1]);
00721
00722 }
00723 else
00724 {
00725 joint_modules_["arm"].req_joint_vel_[0] = 0.0;
00726 joint_modules_["arm"].req_joint_vel_[1] = 0.0;
00727 }
00728
00729
00730 if(joint_modules_["arm"].req_joint_vel_.size()>3 && arm_joint34_button_>=0 && arm_joint34_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[arm_joint34_button_]==1)
00731 {
00732
00733 if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]<0.0)
00734 joint_modules_["arm"].req_joint_vel_[2] = -1*(int)joy_msg->buttons[arm_joint34_button_]*joint_modules_["arm"].steps[2]*run_factor_;
00735 else if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]>0.0)
00736 joint_modules_["arm"].req_joint_vel_[2] = (int)joy_msg->buttons[arm_joint34_button_]*joint_modules_["arm"].steps[2]*run_factor_;
00737 else
00738 joint_modules_["arm"].req_joint_vel_[2] = 0.0;
00739 ROS_DEBUG("cb::arm joint3 velocity: %f",joint_modules_["arm"].req_joint_vel_[2]);
00740
00741
00742 if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]>0.0)
00743 joint_modules_["arm"].req_joint_vel_[3] = (int)joy_msg->buttons[arm_joint34_button_]*joint_modules_["arm"].steps[3]*run_factor_;
00744 else if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]<0.0)
00745 joint_modules_["arm"].req_joint_vel_[3] = -1*(int)joy_msg->buttons[arm_joint34_button_]*joint_modules_["arm"].steps[3]*run_factor_;
00746 else
00747 joint_modules_["arm"].req_joint_vel_[3] = 0.0;
00748 ROS_DEBUG("cb::arm joint4 velocity: %f",joint_modules_["arm"].req_joint_vel_[3]);
00749
00750 }
00751 else
00752 {
00753 joint_modules_["arm"].req_joint_vel_[2] = 0.0;
00754 joint_modules_["arm"].req_joint_vel_[3] = 0.0;
00755 }
00756
00757
00758 if(joint_modules_["arm"].req_joint_vel_.size()>4 && arm_joint56_button_>=0 && arm_joint56_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[arm_joint56_button_]==1)
00759 {
00760
00761 if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]<0.0)
00762 joint_modules_["arm"].req_joint_vel_[4] = -1*(int)joy_msg->buttons[arm_joint56_button_]*joint_modules_["arm"].steps[4]*run_factor_;
00763 else if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]>0.0)
00764 joint_modules_["arm"].req_joint_vel_[4] = (int)joy_msg->buttons[arm_joint56_button_]*joint_modules_["arm"].steps[4]*run_factor_;
00765 else
00766 joint_modules_["arm"].req_joint_vel_[4] = 0.0;
00767 ROS_DEBUG("cb::arm joint5 velocity: %f",joint_modules_["arm"].req_joint_vel_[4]);
00768
00769
00770 if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]>0.0)
00771 joint_modules_["arm"].req_joint_vel_[5] = (int)joy_msg->buttons[arm_joint56_button_]*joint_modules_["arm"].steps[5]*run_factor_;
00772 else if(up_down_>=0 && up_down_<(int)joy_msg->axes.size() && joy_msg->axes[up_down_]<0.0)
00773 joint_modules_["arm"].req_joint_vel_[5] = -1*(int)joy_msg->buttons[arm_joint56_button_]*joint_modules_["arm"].steps[5]*run_factor_;
00774 else
00775 joint_modules_["arm"].req_joint_vel_[5] = 0.0;
00776 ROS_DEBUG("cb::arm joint6 velocity: %f",joint_modules_["arm"].req_joint_vel_[5]);
00777
00778 }
00779 else
00780 {
00781 joint_modules_["arm"].req_joint_vel_[4] = 0.0;
00782 joint_modules_["arm"].req_joint_vel_[5] = 0.0;
00783 }
00784
00785
00786 if(joint_modules_["arm"].req_joint_vel_.size()>5 && arm_joint7_button_>=0 && arm_joint7_button_<(int)joy_msg->buttons.size() && joy_msg->buttons[arm_joint7_button_]==1)
00787 {
00788
00789 if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]<0.0)
00790 {
00791 joint_modules_["arm"].req_joint_vel_[6] = -1*(int)joy_msg->buttons[arm_joint7_button_]*joint_modules_["arm"].steps[6]*run_factor_;
00792
00793 }
00794 else if(left_right_>=0 && left_right_<(int)joy_msg->axes.size() && joy_msg->axes[left_right_]>0.0)
00795 {
00796 joint_modules_["arm"].req_joint_vel_[6] = (int)joy_msg->buttons[arm_joint7_button_]*joint_modules_["arm"].steps[6]*run_factor_;
00797
00798 }
00799 else
00800 joint_modules_["arm"].req_joint_vel_[6] = 0.0;
00801 ROS_DEBUG("cb::arm joint7 velocity: %f",joint_modules_["arm"].req_joint_vel_[6]);
00802 }
00803 else
00804 {
00805 joint_modules_["arm"].req_joint_vel_[6] = 0.0;
00806 }
00807 }
00808
00809 if(has_base_module_ && base_module_.req_vel_.size()==3)
00810 {
00811 if(axis_vx_>=0 && axis_vx_<(int)joy_msg->get_axes_size())
00812 base_module_.req_vel_[0] = joy_msg->axes[axis_vx_]*base_module_.max_vel_[0]*run_factor_;
00813 else
00814 base_module_.req_vel_[0] = 0.0;
00815
00816 if(axis_vy_>=0 && axis_vy_<(int)joy_msg->get_axes_size())
00817 base_module_.req_vel_[1] = joy_msg->axes[axis_vy_]*base_module_.max_vel_[1]*run_factor_;
00818 else
00819 base_module_.req_vel_[1] = 0.0;
00820
00821 if(axis_vth_>=0 && axis_vth_<(int)joy_msg->get_axes_size())
00822 base_module_.req_vel_[2] = joy_msg->axes[axis_vth_]*base_module_.max_vel_[2]*run_factor_;
00823 else
00824 base_module_.req_vel_[2] = 0.0;
00825 }
00826
00827 }
00828
00832 void TeleopCOB::update()
00833 {
00834 if (!joy_active_)
00835 {
00836 if (!stopped_)
00837 {
00838
00839 for(std::map<std::string,joint_module>::iterator module_it=joint_modules_.begin();module_it!=joint_modules_.end();++module_it)
00840 {
00841 for(int i=0; i<module_it->second.req_joint_vel_.size();i++)
00842 {
00843 module_it->second.req_joint_vel_[i] = 0.0;
00844 }
00845 }
00846
00847 if(has_base_module_)
00848 {
00849 for(int i=0; i<3; i++){
00850 base_module_.req_vel_[i]=0;
00851 base_module_.vel_old_[i]=0;
00852 }
00853 }
00854
00855 update_joint_modules();
00856 update_base();
00857 stopped_ = true;
00858 ROS_INFO("stopped all components");
00859 }
00860 return;
00861 }
00862
00863
00864 if(!got_init_values_)
00865 {
00866 if (time_for_init_ < 1.0)
00867 {
00868 ROS_DEBUG("still waiting for initial values, time_for_init_ = %f",time_for_init_);
00869 time_for_init_ = time_for_init_ + 1.0/PUBLISH_FREQ;
00870 return;
00871 }
00872 else
00873 {
00874 ROS_WARN("Timeout waiting for /joint_states message. Setting all init values to 0.0");
00875 setInitValues();
00876 }
00877 }
00878
00879 update_joint_modules();
00880 update_base();
00881 stopped_ = false;
00882 }
00883
00884 void TeleopCOB::update_joint_modules()
00885 {
00886 double dt = 1.0/double(PUBLISH_FREQ);
00887 double horizon = 3.0*dt;
00888
00889 joint_module* jointModule;
00890 for(std::map<std::string,joint_module>::iterator it = joint_modules_.begin();it!=joint_modules_.end();++it)
00891 {
00892 jointModule = (joint_module*)(&(it->second));
00893
00894 trajectory_msgs::JointTrajectory traj;
00895 traj.header.stamp = ros::Time::now()+ros::Duration(0.01);
00896 traj.points.resize(1);
00897 brics_actuator::JointVelocities cmd_vel;
00898 brics_actuator::JointValue joint_vel;
00899 joint_vel.timeStamp = traj.header.stamp;
00900 joint_vel.unit = "rad";
00901 for( int i = 0; i<jointModule->joint_names.size();i++)
00902 {
00903
00904 traj.joint_names.push_back(jointModule->joint_names[i]);
00905 traj.points[0].positions.push_back(jointModule->req_joint_pos_[i] + jointModule->req_joint_vel_[i]*horizon);
00906 traj.points[0].velocities.push_back(jointModule->req_joint_vel_[i]);
00907
00908 joint_vel.value = jointModule->req_joint_vel_[i];
00909 joint_vel.joint_uri = jointModule->joint_names[i];
00910 cmd_vel.velocities.push_back(joint_vel);
00911
00912 jointModule->req_joint_pos_[i] += jointModule->req_joint_vel_[i]*horizon;
00913 }
00914
00915 traj.points[0].time_from_start = ros::Duration(horizon);
00916
00917 jointModule->module_publisher_.publish(traj);
00918 jointModule->module_publisher_brics_.publish(cmd_vel);
00919 }
00920 }
00921
00925 void TeleopCOB::update_base()
00926 {
00927 if(!has_base_module_)
00928 return;
00929 double dt = 1.0/double(PUBLISH_FREQ);
00930 double v[] = {0.0,0.0,0.0};
00931
00932 for( int i =0; i<3; i++)
00933 {
00934
00935 if ((base_module_.req_vel_[i]-base_module_.vel_old_[i])/dt > base_module_.max_acc_[i])
00936 {
00937 v[i] = base_module_.vel_old_[i] + base_module_.max_acc_[i]*dt;
00938 }
00939 else if((base_module_.req_vel_[i]-base_module_.vel_old_[i])/dt < -base_module_.max_acc_[i])
00940 {
00941 v[i] = base_module_.vel_old_[i] - base_module_.max_acc_[i]*dt;
00942 }
00943 else
00944 {
00945 v[i] = base_module_.req_vel_[i];
00946 }
00947 base_module_.vel_old_[i] = v[i];
00948 }
00949
00950 geometry_msgs::Twist cmd;
00951 cmd.linear.x = v[0];
00952 cmd.linear.y = v[1];
00953 cmd.angular.z = v[2];
00954
00955 base_module_.base_publisher_.publish(cmd);
00956 }
00957
00963 int main(int argc,char **argv)
00964 {
00965 ros::init(argc,argv,"teleop_cob");
00966 TeleopCOB teleop_cob;
00967 teleop_cob.init();
00968
00969 ros::Rate loop_rate(PUBLISH_FREQ);
00970 while(teleop_cob.n_.ok())
00971 {
00972 ros::spinOnce();
00973 teleop_cob.update();
00974 loop_rate.sleep();
00975 }
00976
00977 exit(0);
00978 return(0);
00979 }
00980