39 #ifndef ROS_CONTROL_BOILERPLATE__JOYSTICK_MANUAL_CONTROL    40 #define ROS_CONTROL_BOILERPLATE__JOYSTICK_MANUAL_CONTROL    44 #include <sensor_msgs/Joy.h>    47 #include <controller_manager_msgs/SwitchController.h>    48 #include <controller_manager_msgs/LoadController.h>    65     switch_service_ = service_namespace + 
"/controller_manager/switch_controller";
    66     load_service_ = service_namespace + 
"/controller_manager/load_controller";
    75     std::size_t queue_size = 1;
    85   virtual void joyCallback(
const sensor_msgs::Joy::ConstPtr& msg) = 0;
   102       controller_manager_msgs::LoadController service;
   104       std::size_t counter = 0;
   110                                                                 << 
"', trying again");
   123     controller_manager_msgs::SwitchController service;
   124     service.request.strictness = service.request.STRICT;
   147     controller_manager_msgs::SwitchController service;
   148     service.request.strictness = service.request.STRICT;
 void switchToTrajectory()
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
bool using_trajectory_controller_
#define ROS_ERROR_STREAM_NAMED(name, args)
std::vector< std::string > trajectory_controllers_
const std::string parent_name_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber remote_joy_
std::string load_service_
bool call(MReq &req, MRes &res)
ros::ServiceClient switch_controlers_client_
virtual void joyCallback(const sensor_msgs::Joy::ConstPtr &msg)=0
Response to joystick control Button mapping is customized by each class that inherits from this...
#define ROS_INFO_STREAM_NAMED(name, args)
JoystickManualControl(const std::string &parent_name, const std::string &service_namespace)
Constructor. 
std::string switch_service_
#define ROS_WARN_STREAM_THROTTLE_NAMED(period, name, args)
ros::ServiceClient load_controlers_client_
ROSCPP_DECL void spinOnce()
std::vector< std::string > manual_controllers_
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
#define ROS_WARN_STREAM_NAMED(name, args)
bool loadManualControllers()
Load a secondary manual controller.