Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef ROS_CONTROL_BOILERPLATE__JOYSTICK_MANUAL_CONTROL
00040 #define ROS_CONTROL_BOILERPLATE__JOYSTICK_MANUAL_CONTROL
00041
00042
00043 #include <ros/ros.h>
00044 #include <sensor_msgs/Joy.h>
00045
00046
00047 #include <controller_manager_msgs/SwitchController.h>
00048 #include <controller_manager_msgs/LoadController.h>
00049
00050 namespace ros_control_boilerplate
00051 {
00052 class JoystickManualControl
00053 {
00054 public:
00061 JoystickManualControl(const std::string& parent_name, const std::string& service_namespace)
00062 : parent_name_(parent_name)
00063 , using_trajectory_controller_(true)
00064 {
00065 switch_service_ = service_namespace + "/controller_manager/switch_controller";
00066 load_service_ = service_namespace + "/controller_manager/load_controller";
00067
00068
00069 switch_controlers_client_ =
00070 nh_.serviceClient<controller_manager_msgs::SwitchController>(switch_service_);
00071 load_controlers_client_ =
00072 nh_.serviceClient<controller_manager_msgs::LoadController>(load_service_);
00073
00074
00075 std::size_t queue_size = 1;
00076 remote_joy_ = nh_.subscribe("/joy", queue_size, &JoystickManualControl::joyCallback, this);
00077
00078 ROS_INFO_STREAM_NAMED(parent_name_, "JoystickManualControl Ready.");
00079 }
00080
00085 virtual void joyCallback(const sensor_msgs::Joy::ConstPtr& msg) = 0;
00086
00090 bool loadManualControllers()
00091 {
00092
00093 ROS_INFO_STREAM_NAMED(parent_name_, "Waiting for serivces...");
00094 if (!ros::service::waitForService(switch_service_, ros::Duration(10)))
00095 ROS_ERROR_STREAM_NAMED(parent_name_, "Unable to find service " << switch_service_);
00096 if (!ros::service::waitForService(load_service_, ros::Duration(10)))
00097 ROS_ERROR_STREAM_NAMED(parent_name_, "Unable to find service " << load_service_);
00098
00099 for (std::size_t i = 0; i < manual_controllers_.size(); ++i)
00100 {
00101 ROS_INFO_STREAM_NAMED(parent_name_, "Loading controller " << manual_controllers_[i]);
00102 controller_manager_msgs::LoadController service;
00103 service.request.name = manual_controllers_[i];
00104 std::size_t counter = 0;
00105 while (!load_controlers_client_.call(service) && ros::ok())
00106 {
00107 if (counter > 100)
00108 ROS_WARN_STREAM_THROTTLE_NAMED(1.0, parent_name_, "Failed to load controller '"
00109 << manual_controllers_[i]
00110 << "', trying again");
00111 ros::spinOnce();
00112 ros::Duration(0.1).sleep();
00113 counter++;
00114 }
00115 }
00116
00117 return true;
00118 }
00119
00120 void switchToManual()
00121 {
00122
00123 controller_manager_msgs::SwitchController service;
00124 service.request.strictness = service.request.STRICT;
00125
00126 ROS_WARN_STREAM_NAMED(parent_name_, "Switching to MANUAL control");
00127 for (std::size_t i = 0; i < manual_controllers_.size(); ++i)
00128 {
00129 service.request.start_controllers.push_back(manual_controllers_[i]);
00130 }
00131 for (std::size_t i = 0; i < trajectory_controllers_.size(); ++i)
00132 {
00133 service.request.stop_controllers.push_back(trajectory_controllers_[i]);
00134 }
00135
00136
00137 if (!switch_controlers_client_.call(service))
00138 {
00139 ROS_ERROR_STREAM_NAMED(parent_name_, "Failed to switch controllers");
00140 return;
00141 }
00142 }
00143
00144 void switchToTrajectory()
00145 {
00146
00147 controller_manager_msgs::SwitchController service;
00148 service.request.strictness = service.request.STRICT;
00149
00150 ROS_INFO_STREAM_NAMED(parent_name_, "Switching to TRAJECTORY control");
00151 for (std::size_t i = 0; i < manual_controllers_.size(); ++i)
00152 {
00153 service.request.stop_controllers.push_back(manual_controllers_[i]);
00154 }
00155 for (std::size_t i = 0; i < trajectory_controllers_.size(); ++i)
00156 {
00157 service.request.start_controllers.push_back(trajectory_controllers_[i]);
00158 }
00159
00160
00161 if (!switch_controlers_client_.call(service))
00162 {
00163 ROS_ERROR_STREAM_NAMED(parent_name_, "Failed to switch controllers");
00164 return;
00165 }
00166 }
00167
00168 protected:
00169
00170 ros::NodeHandle nh_;
00171
00172
00173 const std::string parent_name_;
00174 std::string switch_service_;
00175 std::string load_service_;
00176
00177
00178 ros::Subscriber remote_joy_;
00179
00180
00181 ros::ServiceClient switch_controlers_client_;
00182 ros::ServiceClient load_controlers_client_;
00183
00184
00185 bool using_trajectory_controller_;
00186
00187
00188 std::vector<std::string> manual_controllers_;
00189 std::vector<std::string> trajectory_controllers_;
00190
00191 };
00192
00193 }
00194
00195 #endif