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>
126 void say(std::string text,
bool blocking);
128 void joy_cb(
const sensor_msgs::Joy::ConstPtr &joy_msg);
143 std::string comp_name = p->first;
144 ROS_DEBUG(
"component name: %s",comp_name.c_str());
148 ROS_WARN(
"invalid component, name: %s",comp_name.c_str());
151 for(std::map<std::string,XmlRpc::XmlRpcValue>::iterator ps=comp_struc.
begin();ps!=comp_struc.
end();++ps)
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)
160 std::string
s((std::string)twist_topic_name);
161 ROS_DEBUG(
"twist_topic_name found = %s",
s.c_str());
165 if(par_name.compare(
"twist_safety_topic_name")==0)
167 ROS_DEBUG(
"twist saftey topic name found");
170 std::string
s((std::string)twist_safety_topic_name);
171 ROS_DEBUG(
"twist_safety_topic_name found = %s",
s.c_str());
175 else if(par_name.compare(
"velocity_topic_name")==0)
180 std::string
s((std::string)vel_group_topic_name);
185 else if(par_name.compare(
"sss_default_target")==0)
187 ROS_DEBUG(
"default target position found");
190 std::string
s((std::string)sss_default_target);
191 ROS_DEBUG(
"sss_default_target found = %s",
s.c_str());
194 else if(par_name.compare(
"joint_velocity")==0)
199 ROS_DEBUG(
"joint_velocity.size: %d \n", joint_velocity.
size());
200 for(
int i=0;i<joint_velocity.
size();i++)
203 double vel((
double)joint_velocity[i]);
204 ROS_DEBUG(
"joint_velocity found = %f",vel);
208 else if(par_name.compare(
"twist_max_velocity")==0)
213 ROS_DEBUG(
"twist_max_velocity.size: %d \n", twist_max_velocity.
size());
214 for(
int i=0;i<twist_max_velocity.
size();i++)
217 double vel((
double)twist_max_velocity[i]);
218 ROS_DEBUG(
"twist_max_velocity found = %f",vel);
222 else if(par_name.compare(
"twist_max_acc")==0)
227 ROS_DEBUG(
"twist_max_acc.size: %d \n", twist_max_acc.
size());
228 for(
int i=0;i<twist_max_acc.
size();i++)
231 double vel((
double)twist_max_acc[i]);
232 ROS_DEBUG(
"twist_max_acc found = %f",vel);
237 ROS_DEBUG(
"%s module stored",comp_name.c_str());
238 component_config_.insert(std::pair<std::string,component_config>(comp_name,tempComponent));
279 ROS_INFO(
"Switched to mode 1: move the base using twist controller");
280 saytext =
"Base mode";
284 ROS_INFO(
"Switched to mode 2: move the actuators to a default position (Trajectory controller)");
285 saytext =
"Default position mode";
289 ROS_INFO(
"Switched to mode 3: move the actuators using joint group velocity controller");
290 saytext =
"Velocity mode";
294 ROS_INFO(
"Switched to mode 4: move the actuators in cartesian mode using twist controller");
295 saytext =
"Cartesian mode";
303 sensor_msgs::JoyFeedbackArray joy_fb;
304 joy_fb.array.resize(4);
305 for (
unsigned int i=0; i<4; i++)
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]);
321 geometry_msgs::Twist base_cmd;
324 for(
unsigned int i=0; i<3; i++)
333 for(
int i =0; i<3; i++)
376 cob_sound::SayGoal say_goal;
377 say_goal.text = text;
390 cob_light::LightMode light;
391 light.mode = cob_light::LightModes::FLASH;
394 std_msgs::ColorRGBA
color;
400 light.colors.push_back(
color);
401 cob_light::SetLightModeGoal light_goal;
402 light_goal.mode = light;
427 ROS_INFO(
"Switch mode button pressed");
464 ROS_INFO(
"Waiting for script server");
471 say(
"init and recover",
true);
475 std::string comp_name = p->first;
477 ROS_INFO(
"Init %s",comp_name.c_str());
478 std::string saytext = comp_name;
479 std::replace(saytext.begin(), saytext.end(),
'_',
' ');
487 std::string saytext =
"Init " + comp_name +
" failed";
488 std::replace(saytext.begin(), saytext.end(),
'_',
' ');
492 ROS_INFO(
"Recover %s",comp_name.c_str());
498 std::string saytext =
"Recover " + comp_name +
" failed";
499 std::replace(saytext.begin(), saytext.end(),
'_',
' ');
511 ROS_DEBUG(
"Mode 1: Move the base using twist controller");
572 ROS_DEBUG(
"Mode 2: Move the actuators to a default position (Trajectory controller)");
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)
582 ROS_DEBUG(
"%s_sss_default_target_button parameter not defined",comp_name.c_str());
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)
590 std::string saytext =
"Move " + comp_name +
" to " +
script_goal_.parameter_name;
591 std::replace(saytext.begin(), saytext.end(),
'_',
' ');
601 ROS_DEBUG(
"Mode 3: Move the actuators using the group velocity controller");
605 int component_joint_button_temp = -1;
606 std::string comp_name = p->first;
608 for(
int i=0; i < size; ++i)
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;
616 if(!(comp_name.find(
"left") != std::string::npos) && !(comp_name.find(
"right") != std::string::npos))
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)
621 ROS_INFO(
"%s velocity mode",comp_name.c_str());
637 else if(!(comp_name.find(
"left") != std::string::npos) && (comp_name.find(
"right") != std::string::npos))
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)
642 ROS_INFO(
"%s velocity mode",comp_name.c_str());
658 else if((comp_name.find(
"left") != std::string::npos) && !(comp_name.find(
"right") != std::string::npos))
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)
663 ROS_INFO(
"%s velocity mode",comp_name.c_str());
686 ROS_DEBUG(
"Mode 4: Move the actuators using the twist controller");
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)
697 ROS_INFO(
"%s twist mode",comp_name.c_str());
701 twist_cmd.linear.x =0.0;
705 twist_cmd.linear.y =0.0;
709 twist_cmd.linear.z =0.0;
713 twist_cmd.angular.x =0.0;
717 twist_cmd.angular.y =0.0;
721 twist_cmd.angular.z =0.0;
736 ROS_ERROR(
"parameter components does not exist on ROS Parameter Server, aborting...");
797 cob_light::LightMode light;
798 light.mode = cob_light::LightModes::FLASH;
801 std_msgs::ColorRGBA
color;
807 light.colors.push_back(
color);
813 light.colors.clear();
814 light.colors.push_back(
color);
819 int main(
int argc,
char** argv)
826 while(cob_teleop.
n_.
ok())