Go to the documentation of this file.
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);
129 int wantedController = 0;
130 std::cout <<
"Choose the # of the controller you want to use:\n";
131 std::cin >> wantedController;
135 ROS_ERROR(
"Invalid number for controller choice.");
155 ROS_INFO(
"Use the arrows in Webots window to move the robot.");
156 ROS_INFO(
"Press the End key to stop the node.");
162 ROS_ERROR(
"Failed to call service time_step for next step.");
void controllerNameCallback(const std_msgs::String::ConstPtr &name)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::ServiceClient enableKeyboardClient
void keyboardCallback(const webots_ros::Int32Stamped::ConstPtr &value)
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void spinOnce()
ROSCPP_DECL void shutdown()
static std::vector< std::string > controllerList
ros::ServiceClient leftWheelClient
static int controllerCount
uint32_t getNumPublishers() const
static std::string controllerName
ros::ServiceClient timeStepClient
webots_ros::set_float leftWheelSrv
ros::ServiceClient rightWheelClient
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())
webots_ros::set_int enableKeyboardSrv
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
webots_ros::set_float rightWheelSrv
webots_ros::set_int timeStepSrv
int main(int argc, char **argv)
webots_ros
Author(s): Cyberbotics
autogenerated on Wed Mar 2 2022 01:15:14