Revision 2bd58ddb
ID | 2bd58ddb37ca8f91b0127148c33b47f3673adb42 |
updated teleop; now works for multiple scoutsim robots
scout/scoutsim/src/scout_teleop.cpp | ||
---|---|---|
1 | 1 |
#include "scout_teleop.h" |
2 | 2 |
|
3 |
TeleopScout::TeleopScout(std::string scoutname) |
|
3 |
using namespace std; |
|
4 |
|
|
5 |
TeleopScout::TeleopScout(string scoutname) |
|
4 | 6 |
{ |
5 | 7 |
fl_set = fr_set = bl_set = br_set = true; |
6 | 8 |
fl_speed = fr_speed = bl_speed = br_speed = 0; |
... | ... | |
89 | 91 |
|
90 | 92 |
int main(int argc, char** argv) |
91 | 93 |
{ |
92 |
ros::init(argc, argv, "scout_teleop"); |
|
93 |
TeleopScout teleop_scout = TeleopScout("scout1"); |
|
94 |
string scoutname = ""; |
|
95 |
if(argc != 2) |
|
96 |
{ |
|
97 |
cout << "Opens up a teleop process to send input to the motors" << endl; |
|
98 |
cout << "(Remember to create a scout_teleop_userinput process as well to actually capture keyboard input!)" << endl; |
|
99 |
cout << "Usage: " << argv[0] <<" <scoutname>" << endl; |
|
100 |
exit(0); |
|
101 |
} |
|
102 |
|
|
103 |
scoutname = argv[1]; |
|
104 |
ros::init(argc, argv, scoutname+"_scout_teleop"); |
|
105 |
TeleopScout teleop_scout = TeleopScout(scoutname); |
|
94 | 106 |
|
95 | 107 |
teleop_scout.keyListenerLoop(); |
96 | 108 |
|
scout/scoutsim/src/scout_teleop_userinput.cpp | ||
---|---|---|
1 | 1 |
#include "scout_teleop_userinput.h" |
2 | 2 |
|
3 |
TeleopInput::TeleopInput(std::string scoutname) |
|
3 |
using namespace std; |
|
4 |
|
|
5 |
TeleopInput::TeleopInput(string scoutname) |
|
4 | 6 |
{ |
5 |
input_pub = node.advertise<scoutsim::teleop_input>(scoutname+"/teleop_input", QUEUE_SIZE); |
|
7 |
input_pub = node.advertise<scoutsim::teleop_input>( |
|
8 |
scoutname+"/teleop_input", QUEUE_SIZE); |
|
6 | 9 |
kfd = 0; |
7 | 10 |
|
8 | 11 |
// get the console in raw mode |
... | ... | |
55 | 58 |
|
56 | 59 |
int main(int argc, char** argv) |
57 | 60 |
{ |
58 |
ros::init(argc, argv, "scout_teleop_userinput"); |
|
59 |
TeleopInput teleop_input = TeleopInput("scout1"); |
|
61 |
string scoutname = ""; |
|
62 |
if(argc != 2) |
|
63 |
{ |
|
64 |
cout << "Opens up a teleop process to read in user keyboard input" << endl; |
|
65 |
cout << "(Remember to have a scout_teleop process running simulatenously to actually process this input!)"<< endl; |
|
66 |
cout << "Usage: " << argv[0] <<" <scoutname>" << endl; |
|
67 |
exit(0); |
|
68 |
} |
|
69 |
|
|
70 |
scoutname = argv[1]; |
|
71 |
ros::init(argc, argv, scoutname +"_scout_teleop_userinput"); |
|
72 |
TeleopInput teleop_input = TeleopInput(scoutname); |
|
60 | 73 |
//signal(SIGINT,quit); |
61 | 74 |
teleop_input.keyLoop(); |
62 |
|
|
75 |
|
|
63 | 76 |
return(0); |
64 | 77 |
} |
65 | 78 |
|
Also available in: Unified diff