Go to the documentation of this file.00001
00013 #include <geometry_msgs/Twist.h>
00014 #include <ros/ros.h>
00015 #include <rovio_shared/head_ctrl.h>
00016 #include <rovio_ctrl/rovio_teleop.h>
00017 #include <rovio_shared/man_drv.h>
00018 #include <rovio_shared/wav_play.h>
00019 #include <sensor_msgs/Joy.h>
00020 #include <string>
00021
00022 using namespace std;
00023
00024 teleop_controller::teleop_controller()
00025 {
00026
00027 if (!node.getParam(ROVIO_WAV, rovio_wav))
00028 {
00029 ROS_ERROR("Parameter %s not found.", ROVIO_WAV);
00030 exit(-1);
00031 }
00032
00033
00034 cmd_vel = node.advertise<geometry_msgs::Twist>("cmd_vel", 10);
00035 head_ctrl = node.serviceClient<rovio_shared::head_ctrl>("head_ctrl");
00036 wav_play = node.serviceClient<rovio_shared::wav_play>("wav_play");
00037
00038
00039 joy_sub = node.subscribe<sensor_msgs::Joy>("joy", 10, &teleop_controller::joy_cback, this);
00040
00041 ROS_INFO("Rovio Teleop Started");
00042 }
00043
00044 void teleop_controller::joy_cback(const sensor_msgs::Joy::ConstPtr& joy)
00045 {
00046
00047 rovio_shared::man_drv drv;
00048 rovio_shared::head_ctrl head;
00049 rovio_shared::wav_play wav;
00050
00051
00052 head.request.head_pos = -1;
00053 if (joy->buttons.at(0) == 1)
00054 head.request.head_pos = rovio_shared::head_ctrl::Request::HEAD_DOWN;
00055 else if (joy->buttons.at(1) == 1)
00056 head.request.head_pos = rovio_shared::head_ctrl::Request::HEAD_MIDDLE;
00057 else if (joy->buttons.at(2) == 1)
00058 head.request.head_pos = rovio_shared::head_ctrl::Request::HEAD_UP;
00059
00060
00061 if (head.request.head_pos != -1)
00062
00063 head_ctrl.call(head);
00064
00065
00066 wav.request.f = "";
00067 wav.request.f.append(rovio_wav);
00068 if (joy->buttons.at(4) == 1)
00069 wav.request.f.append("/G11.wav");
00070 else if (joy->buttons.at(5) == 1)
00071 wav.request.f.append("/G03.wav");
00072 else if (joy->buttons.at(6) == 1)
00073 wav.request.f.append("/G27a.wav");
00074 else if (joy->buttons.at(7) == 1)
00075 wav.request.f.append("/G34.wav");
00076 else
00077 wav.request.f = "";
00078
00079
00080 if (wav.request.f.size() > 0)
00081
00082 wav_play.call(wav);
00083
00084
00085 geometry_msgs::Twist twist;
00086
00087 twist.linear.x = joy->axes.at(1) * THROTTLE;
00088 twist.linear.y = joy->axes.at(0) * THROTTLE;
00089 twist.linear.z = 0;
00090
00091 twist.angular.x = 0;
00092 twist.angular.y = 0;
00093 twist.angular.z = joy->axes.at(2) * THROTTLE;
00094
00095 cmd_vel.publish(twist);
00096 }
00097
00098 int main(int argc, char **argv)
00099 {
00100
00101 ros::init(argc, argv, "rovio_teleop");
00102
00103
00104 teleop_controller controller;
00105
00106
00107 ros::spin();
00108 }