sim_joy.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <sensor_msgs/Joy.h>
3 #include <geometry_msgs/TwistStamped.h>
4 
5 #include <string.h>
6 #include <vector>
7 
8 #define COMMAND_TIMEOUT_SEC 0.5
9 
10 const int PUBLISH_FREQ = 20;
11 
13 {
14 public:
15  SimOperator(unsigned int numOfRobots);
16 
17  void receiveJoyMessage(const sensor_msgs::Joy::ConstPtr& msg);
18  void sendControl();
19 
20 private:
21  unsigned int mNumberOfRobots;
24 
26  std::vector<ros::Publisher> mCommandPublisher;
27  std::vector<geometry_msgs::Twist> mCommand;
28 };
29 
30 SimOperator::SimOperator(unsigned int numOfRobots)
31 {
32  mNumberOfRobots = numOfRobots;
33  mMaxLinearVelocity = 1.0;
34  mMaxAngularVelocity = 1.0;
35 
36  ros::NodeHandle node;
37 
38  // Subscribe to joystick
40 
41  // Publish commands for every robot in the simulation
42  char topic[50];
43  for(unsigned int i = 0; i < mNumberOfRobots; i++)
44  {
45  if(mNumberOfRobots > 1)
46  sprintf(topic, "/robot_%d/cmd_vel", i);
47  else
48  sprintf(topic, "/cmd_vel");
49  mCommandPublisher.push_back(node.advertise<geometry_msgs::Twist>(topic, 1));
50 
51  geometry_msgs::Twist twist;
52  mCommand.push_back(twist);
53  }
54 }
55 
56 void SimOperator::receiveJoyMessage(const sensor_msgs::Joy::ConstPtr& msg)
57 {
58  for(unsigned int i = 0; i < mNumberOfRobots; i++)
59  {
60  if(msg->buttons[i])
61  {
62  mCommand[i].linear.x = msg->axes[1] * mMaxLinearVelocity;
63  mCommand[i].angular.z = msg->axes[0] * mMaxAngularVelocity;
64  }else
65  {
66  mCommand[i].linear.x = 0;
67  mCommand[i].angular.z = 0;
68  }
69  }
70 }
71 
73 {
74  for(unsigned int i = 0; i < mNumberOfRobots; i++)
75  {
76  mCommandPublisher[i].publish(mCommand[i]);
77  }
78 }
79 
80 int main(int argc, char** argv)
81 {
82  // init the ROS node
83  ros::init(argc,argv,"SimController");
84  ros::NodeHandle node;
85 
86  unsigned int num = 1;
87  if(argc > 1)
88  {
89  num = (unsigned int)atoi(argv[1]);
90  if(num > 6) num = 6;
91  }
92 
93  ROS_INFO("Using Joystick to operate %d robots in simulation!", num);
94  SimOperator simOp(num);
95 
96  ros::Rate pub_rate(PUBLISH_FREQ);
97  while (node.ok())
98  {
99  ros::spinOnce();
100  simOp.sendControl();
101  pub_rate.sleep();
102  }
103 
104  return 0;
105 }
106 
std::vector< ros::Publisher > mCommandPublisher
Definition: sim_joy.cpp:26
ros::Subscriber mJoySubscriber
Definition: sim_joy.cpp:25
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void receiveJoyMessage(const sensor_msgs::Joy::ConstPtr &msg)
Definition: sim_joy.cpp:56
std::vector< geometry_msgs::Twist > mCommand
Definition: sim_joy.cpp:27
#define ROS_INFO(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
SimOperator(unsigned int numOfRobots)
Definition: sim_joy.cpp:30
void sendControl()
Definition: sim_joy.cpp:72
bool sleep()
int main(int argc, char **argv)
Definition: sim_joy.cpp:80
double mMaxLinearVelocity
Definition: sim_joy.cpp:22
const int PUBLISH_FREQ
Definition: sim_joy.cpp:10
bool ok() const
ROSCPP_DECL void spinOnce()
double mMaxAngularVelocity
Definition: sim_joy.cpp:23
unsigned int mNumberOfRobots
Definition: sim_joy.cpp:21


nav2d_remote
Author(s): Sebastian Kasperski
autogenerated on Thu Jun 6 2019 19:20:51