17 #include <webots_ros/Int32Stamped.h> 19 #include <webots_ros/set_float.h> 20 #include <webots_ros/set_int.h> 22 #include <webots_ros/robot_get_device_list.h> 24 #include <std_msgs/String.h> 61 ROS_INFO(
"User stopped the 'keyboard_teleop' node.");
67 int key = value->data;
105 ROS_ERROR(
"Failed to send new position commands to the robot.");
110 int main(
int argc,
char **argv) {
115 signal(SIGINT,
quit);
130 int wantedController = 0;
131 std::cout <<
"Choose the # of the controller you want to use:\n";
132 std::cin >> wantedController;
136 ROS_ERROR(
"Invalid number for controller choice.");
156 ROS_INFO(
"Use the arrows in Webots window to move the robot.");
157 ROS_INFO(
"Press the End key to stop the node.");
163 ROS_ERROR(
"Failed to call service time_step for next step.");
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void controllerNameCallback(const std_msgs::String::ConstPtr &name)
void keyboardCallback(const webots_ros::Int32Stamped::ConstPtr &value)
ros::ServiceClient timeStepClient
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static std::vector< std::string > controllerList
ros::ServiceClient leftWheelClient
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
static int controllerCount
static std::string controllerName
webots_ros::set_float leftWheelSrv
uint32_t getNumPublishers() const
ros::ServiceClient rightWheelClient
webots_ros::set_int enableKeyboardSrv
ROSCPP_DECL void shutdown()
webots_ros::set_int timeStepSrv
ROSCPP_DECL void spinOnce()
webots_ros::set_float rightWheelSrv
ros::ServiceClient enableKeyboardClient
int main(int argc, char **argv)