Go to the documentation of this file.
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>
52 class JoystickManualControl
64 switch_service_ = service_namespace +
"/controller_manager/switch_controller";
65 load_service_ = service_namespace +
"/controller_manager/load_controller";
72 std::size_t queue_size = 1;
82 virtual void joyCallback(
const sensor_msgs::Joy::ConstPtr& msg) = 0;
99 controller_manager_msgs::LoadController service;
101 std::size_t counter = 0;
119 controller_manager_msgs::SwitchController service;
120 service.request.strictness = service.request.STRICT;
143 controller_manager_msgs::SwitchController service;
144 service.request.strictness = service.request.STRICT;
#define ROS_WARN_STREAM_THROTTLE_NAMED(period, name, args)
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.
ros::ServiceClient switch_controlers_client_
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void spinOnce()
ros::Subscriber remote_joy_
void switchToTrajectory()
ros::ServiceClient load_controlers_client_
std::string load_service_
JoystickManualControl(const std::string &parent_name, const std::string &service_namespace)
Constructor.
#define ROS_ERROR_STREAM_NAMED(name, args)
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())
std::vector< std::string > manual_controllers_
#define ROS_WARN_STREAM_NAMED(name, args)
std::vector< std::string > trajectory_controllers_
const std::string parent_name_
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
#define ROS_INFO_STREAM_NAMED(name, args)
bool using_trajectory_controller_
bool loadManualControllers()
Load a secondary manual controller.
std::string switch_service_