Go to the documentation of this file.
2 #include <sensor_msgs/Joy.h>
3 #include <geometry_msgs/TwistStamped.h>
8 #define COMMAND_TIMEOUT_SEC 0.5
46 sprintf(topic,
"/robot_%d/cmd_vel", i);
48 sprintf(topic,
"/cmd_vel");
51 geometry_msgs::Twist twist;
80 int main(
int argc,
char** argv)
89 num = (
unsigned int)atoi(argv[1]);
93 ROS_INFO(
"Using Joystick to operate %d robots in simulation!", num);
double mMaxAngularVelocity
unsigned int mNumberOfRobots
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
std::vector< ros::Publisher > mCommandPublisher
ros::Subscriber mJoySubscriber
ROSCPP_DECL void spinOnce()
Publisher advertise(AdvertiseOptions &ops)
std::vector< geometry_msgs::Twist > mCommand
void receiveJoyMessage(const sensor_msgs::Joy::ConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
SimOperator(unsigned int numOfRobots)
double mMaxLinearVelocity
int main(int argc, char **argv)
nav2d_remote
Author(s): Sebastian Kasperski
autogenerated on Wed Mar 2 2022 00:37:43