atlasmv_command_publisher.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 #include <iostream>
33 #include "ros/ros.h"
34 
35 #include <signal.h>
36 
37 #include <atlasmv_base/AtlasmvMotionCommand.h>
38 #include <atlasmv_base/c_atlasmv.h>
39 
41 #include <math.h>
42 
43 using namespace ros;
44 using namespace std;
45 
46 atlasmv_base::AtlasmvMotionCommand command;
48 bool in_reverse=false;
49 int last_value=-32768.;
50 Publisher commandPublisher;
51 
52 
53 void GamepadSearch(int value,void*parameters)
54 {
55  atlasmv_base::AtlasmvMotionCommand command_local;
56 
57  if(value==1)
58  {
59  command_local.dir=0;
60  command_local.speed=0.2;
61  command_local.lifetime=INFINITY;
62  command_local.priority=1;
63  command_local.header.stamp=ros::Time::now();
64  commandPublisher.publish(command_local);
65  }
66  else
67  {
68  command_local.dir=0;
69  command_local.speed=0.0;
70  command_local.lifetime=0.1;
71  command_local.priority=1;
72  command_local.header.stamp=ros::Time::now();
73  commandPublisher.publish(command_local);
74  }
75 
76 }
77 
78 
79 void GamepadSpeed(int value,void*userdata)
80 {
82 
83  double speed=(((double)(value)/32768. + 1)/2);
84  last_value=value;
85 
86  if(!in_reverse)
87  speed=speed*p->max_forward_speed;
88  else
89  speed=speed*p->max_backward_speed;
90 
91  cout<<"speed: "<<speed<<endl;
92  command.speed=speed;
93  command.lifetime=1;//INFINITY;
94  command.priority=3;
95  command.header.stamp=ros::Time::now();
96  commandPublisher.publish(command);
97 }
98 
99 void GamepadReverse(int value,void*parameters)
100 {
101  if(value)
102  in_reverse=1;
103  else
104  in_reverse=0;
105  command.priority=3;
106  GamepadSpeed(last_value,parameters);
107 }
108 
109 void GamepadDir(int value,void*userdata)
110 {
112 
113  double dir=((double)(-value)/32768.);
114 
115  if(dir>0)
116  dir*=fabs(p->maximum_dir);
117  else
118  dir*=fabs(p->minimum_dir);
119 
120  command.dir=dir;
121 // command.dir=0.0;
122  command.lifetime=INFINITY;
123  command.priority=3;
124  command.header.stamp=ros::Time::now();
125  commandPublisher.publish(command);
126 }
127 
128 void GamepadZeroSteering(int value,void*userdata)
129 {
130  command.dir=0;
131  command.lifetime=INFINITY;
132  command.priority=3;
133  command.header.stamp=ros::Time::now();
134  commandPublisher.publish(command);
135 }
136 
137 void GamepadDisconnect(int value,void*userdata)
138 {
139  command.dir=0;
140  command.speed=0;
141  command.lifetime=0.2;
142  command.priority=3;
143  command.header.stamp=ros::Time::now();
144  commandPublisher.publish(command);
145 }
146 
147 int main(int argc,char**argv)
148 {
149  TYPE_atlasmv_public_params parameters;
150 
151  // Initialize ROS
152  init(argc,argv,"atlasmv_command_publisher");
153 
154  NodeHandle nh("~");
155 
156  class_gamepad gamepad;
157 
158  char*dev=(char*)malloc(1024*sizeof(char));
159  std::string dev_s;
160 
161  nh.param("maximum_dir", parameters.maximum_dir,0.355);
162  nh.param("minimum_dir", parameters.minimum_dir,-0.38);
163  nh.param("max_forward_speed", parameters.max_forward_speed,4.0);
164  nh.param("max_backward_speed", parameters.max_backward_speed,-1.);
165  nh.param("device_gamepad",dev_s,(std::string)"/dev/input/js0");
166 
167  strcpy(dev,dev_s.c_str());
168 
169  cout<<endl<<"Gamepad device: "<<dev_s<<endl;
170  int ret=gamepad.StartComm(dev);
171  gamepad.plerr(ret);
172 
173  //Search mode (advance at low speed with zero steering)
174  ret=gamepad.RegisterCallback(gamepad.BUTTON,3,GamepadSearch,&parameters);
175  gamepad.plerr(ret);
176 
177  //Reverse mode
178  ret=gamepad.RegisterCallback(gamepad.BUTTON,0,GamepadReverse,&parameters);
179  gamepad.plerr(ret);
180 
181  //Forward motion of the atlas robots
182  ret=gamepad.RegisterCallback(gamepad.AXIS,5,GamepadSpeed,&parameters);
183  gamepad.plerr(ret);
184 
185  //Forward motion of the atlas robots
186  ret=gamepad.RegisterCallback(gamepad.BUTTON,6,GamepadDisconnect,&parameters);
187  gamepad.plerr(ret);
188 
189  //Forward motion of the atlas robots
190  ret=gamepad.RegisterCallback(gamepad.BUTTON,7,GamepadDisconnect,&parameters);
191  gamepad.plerr(ret);
192 
193  //Forward motion of the atlas robots
194  ret=gamepad.RegisterCallback(gamepad.BUTTON,2,GamepadZeroSteering,&parameters);
195  gamepad.plerr(ret);
196 
197  //Direction of the atlas robots
198  ret=gamepad.RegisterCallback(gamepad.AXIS,0,GamepadDir,&parameters);
199  gamepad.plerr(ret);
200 
201  /*Publisher*/ commandPublisher = nh.advertise<atlasmv_base::AtlasmvMotionCommand>("/atlasmv/base/motion", 1000);
203 
204  command.lifetime=INFINITY;
205 
206 
207  Rate r(50);//Hz
208 
209  while(ros::ok())//quits on SIGINT
210  {
211  gamepad.Dispatch(0);
212 // cout<<command<<endl;
213  spinOnce();
214  r.sleep();
215  }
216 }
Publisher commandPublisherPtr
Gamepad communication class declaration generic code.
void GamepadDisconnect(int value, void *userdata)
void GamepadZeroSteering(int value, void *userdata)
c_atlasmv.h file for this module. Includes, global vars, function prototypes, etc.
void plerr(int ret)
Print local error function This function prints the error present in the err variable (this is a priv...
int Dispatch(bool debug=false)
This function checks the gamepad status and calls the respective callback.
double max_forward_speed
Definition: c_atlasmv.h:100
void GamepadReverse(int value, void *parameters)
Publisher commandPublisher
atlasmv_base::AtlasmvMotionCommand command
int main(int argc, char **argv)
void GamepadSpeed(int value, void *userdata)
void GamepadDir(int value, void *userdata)
double dir
Definition: atlasmv.h:182
double minimum_dir
Definition: c_atlasmv.h:116
double max_backward_speed
Definition: c_atlasmv.h:101
double speed
Definition: atlasmv.h:182
int RegisterCallback(e_type type, int id, void(*callback)(int value, void *data), void *data)
Register a callback for a specific button or axis.
void GamepadSearch(int value, void *parameters)
typedef that includes all params that define atlasmv robot
Definition: c_atlasmv.h:96
int StartComm(const char *device)
Initialize comm with the gamepad.
double maximum_dir
Definition: c_atlasmv.h:115


atlasmv_base
Author(s): David Gameiro, Jorge Almeida
autogenerated on Mon Mar 2 2015 01:31:28