00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00032 #include <iostream>
00033 #include "ros/ros.h"
00034
00035 #include <signal.h>
00036
00037 #include <atlasmv_base/AtlasmvMotionCommand.h>
00038 #include <c_atlasmv.h>
00039
00040 #include "class_gamepad.h"
00041 #include <math.h>
00042
00043 using namespace ros;
00044 using namespace std;
00045
00046 atlasmv_base::AtlasmvMotionCommand command;
00047 Publisher commandPublisherPtr;
00048 bool in_reverse=false;
00049 int last_value=-32768.;
00050 Publisher commandPublisher;
00051
00052
00053 void GamepadSearch(int value,void*parameters)
00054 {
00055 atlasmv_base::AtlasmvMotionCommand command_local;
00056
00057 if(value==1)
00058 {
00059 command_local.dir=0;
00060 command_local.speed=0.2;
00061 command_local.lifetime=INFINITY;
00062 command_local.priority=1;
00063 command_local.header.stamp=ros::Time::now();
00064 commandPublisher.publish(command_local);
00065 }
00066 else
00067 {
00068 command_local.dir=0;
00069 command_local.speed=0.0;
00070 command_local.lifetime=0.1;
00071 command_local.priority=1;
00072 command_local.header.stamp=ros::Time::now();
00073 commandPublisher.publish(command_local);
00074 }
00075
00076 }
00077
00078
00079 void GamepadSpeed(int value,void*userdata)
00080 {
00081 TYPE_atlasmv_public_params*p=(TYPE_atlasmv_public_params*)userdata;
00082
00083 double speed=(((double)(value)/32768. + 1)/2);
00084 last_value=value;
00085
00086 if(!in_reverse)
00087 speed=speed*p->max_forward_speed;
00088 else
00089 speed=speed*p->max_backward_speed;
00090
00091 cout<<"speed: "<<speed<<endl;
00092 command.speed=speed;
00093 command.lifetime=1;
00094 command.priority=3;
00095 command.header.stamp=ros::Time::now();
00096 commandPublisher.publish(command);
00097 }
00098
00099 void GamepadReverse(int value,void*parameters)
00100 {
00101 if(value)
00102 in_reverse=1;
00103 else
00104 in_reverse=0;
00105 command.priority=3;
00106 GamepadSpeed(last_value,parameters);
00107 }
00108
00109 void GamepadDir(int value,void*userdata)
00110 {
00111 TYPE_atlasmv_public_params*p=(TYPE_atlasmv_public_params*)userdata;
00112
00113 double dir=((double)(-value)/32768.);
00114
00115 if(dir>0)
00116 dir*=fabs(p->maximum_dir);
00117 else
00118 dir*=fabs(p->minimum_dir);
00119
00120 command.dir=dir;
00121
00122 command.lifetime=INFINITY;
00123 command.priority=3;
00124 command.header.stamp=ros::Time::now();
00125 commandPublisher.publish(command);
00126 }
00127
00128 void GamepadZeroSteering(int value,void*userdata)
00129 {
00130 command.dir=0;
00131 command.lifetime=INFINITY;
00132 command.priority=3;
00133 command.header.stamp=ros::Time::now();
00134 commandPublisher.publish(command);
00135 }
00136
00137 void GamepadDisconnect(int value,void*userdata)
00138 {
00139 command.dir=0;
00140 command.speed=0;
00141 command.lifetime=0.2;
00142 command.priority=3;
00143 command.header.stamp=ros::Time::now();
00144 commandPublisher.publish(command);
00145 }
00146
00147 int main(int argc,char**argv)
00148 {
00149 TYPE_atlasmv_public_params parameters;
00150
00151
00152 init(argc,argv,"atlasmv_command_publisher");
00153
00154 NodeHandle nh("~");
00155
00156 class_gamepad gamepad;
00157
00158 char*dev=(char*)malloc(1024*sizeof(char));
00159 std::string dev_s;
00160
00161 nh.param("maximum_dir", parameters.maximum_dir,0.355);
00162 nh.param("minimum_dir", parameters.minimum_dir,-0.38);
00163 nh.param("max_forward_speed", parameters.max_forward_speed,4.0);
00164 nh.param("max_backward_speed", parameters.max_backward_speed,-1.);
00165 nh.param("device_gamepad",dev_s,(std::string)"/dev/input/js0");
00166
00167 strcpy(dev,dev_s.c_str());
00168
00169 cout<<endl<<"Gamepad device: "<<dev_s<<endl;
00170 int ret=gamepad.StartComm(dev);
00171 gamepad.plerr(ret);
00172
00173
00174 ret=gamepad.RegisterCallback(gamepad.BUTTON,3,GamepadSearch,¶meters);
00175 gamepad.plerr(ret);
00176
00177
00178 ret=gamepad.RegisterCallback(gamepad.BUTTON,0,GamepadReverse,¶meters);
00179 gamepad.plerr(ret);
00180
00181
00182 ret=gamepad.RegisterCallback(gamepad.AXIS,5,GamepadSpeed,¶meters);
00183 gamepad.plerr(ret);
00184
00185
00186 ret=gamepad.RegisterCallback(gamepad.BUTTON,6,GamepadDisconnect,¶meters);
00187 gamepad.plerr(ret);
00188
00189
00190 ret=gamepad.RegisterCallback(gamepad.BUTTON,7,GamepadDisconnect,¶meters);
00191 gamepad.plerr(ret);
00192
00193
00194 ret=gamepad.RegisterCallback(gamepad.BUTTON,2,GamepadZeroSteering,¶meters);
00195 gamepad.plerr(ret);
00196
00197
00198 ret=gamepad.RegisterCallback(gamepad.AXIS,0,GamepadDir,¶meters);
00199 gamepad.plerr(ret);
00200
00201 commandPublisher = nh.advertise<atlasmv_base::AtlasmvMotionCommand>("/atlasmv/base/motion", 1000);
00202 commandPublisherPtr=commandPublisher;
00203
00204 command.lifetime=INFINITY;
00205
00206
00207 Rate r(50);
00208
00209 while(ros::ok())
00210 {
00211 gamepad.Dispatch(0);
00212
00213 spinOnce();
00214 r.sleep();
00215 }
00216 }