#include <joystick_manual_control.h>
Public Member Functions | |
| 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. | |
| JoystickManualControl (const std::string &parent_name, const std::string &service_namespace) | |
| Constructor. | |
| bool | loadManualControllers () |
| Load a secondary manual controller. | |
| void | switchToManual () |
| void | switchToTrajectory () |
Protected Attributes | |
| ros::ServiceClient | load_controlers_client_ |
| std::string | load_service_ |
| std::vector< std::string > | manual_controllers_ |
| ros::NodeHandle | nh_ |
| const std::string | parent_name_ |
| ros::Subscriber | remote_joy_ |
| ros::ServiceClient | switch_controlers_client_ |
| std::string | switch_service_ |
| std::vector< std::string > | trajectory_controllers_ |
| bool | using_trajectory_controller_ |
Definition at line 52 of file joystick_manual_control.h.
| ros_control_boilerplate::JoystickManualControl::JoystickManualControl | ( | const std::string & | parent_name, |
| const std::string & | service_namespace | ||
| ) | [inline] |
Constructor.
| parent_name | - name of parent class, only used for namespacing logging debug output |
| service_namespace | - prefix to controller manager service, or blank. do not add trailing "/" |
Definition at line 61 of file joystick_manual_control.h.
| virtual void ros_control_boilerplate::JoystickManualControl::joyCallback | ( | const sensor_msgs::Joy::ConstPtr & | msg | ) | [pure virtual] |
Response to joystick control Button mapping is customized by each class that inherits from this.
| bool ros_control_boilerplate::JoystickManualControl::loadManualControllers | ( | ) | [inline] |
Load a secondary manual controller.
Definition at line 90 of file joystick_manual_control.h.
| void ros_control_boilerplate::JoystickManualControl::switchToManual | ( | ) | [inline] |
Definition at line 120 of file joystick_manual_control.h.
| void ros_control_boilerplate::JoystickManualControl::switchToTrajectory | ( | ) | [inline] |
Definition at line 144 of file joystick_manual_control.h.
ros::ServiceClient ros_control_boilerplate::JoystickManualControl::load_controlers_client_ [protected] |
Definition at line 182 of file joystick_manual_control.h.
std::string ros_control_boilerplate::JoystickManualControl::load_service_ [protected] |
Definition at line 175 of file joystick_manual_control.h.
std::vector<std::string> ros_control_boilerplate::JoystickManualControl::manual_controllers_ [protected] |
Definition at line 188 of file joystick_manual_control.h.
Definition at line 170 of file joystick_manual_control.h.
const std::string ros_control_boilerplate::JoystickManualControl::parent_name_ [protected] |
Definition at line 173 of file joystick_manual_control.h.
Definition at line 178 of file joystick_manual_control.h.
ros::ServiceClient ros_control_boilerplate::JoystickManualControl::switch_controlers_client_ [protected] |
Definition at line 181 of file joystick_manual_control.h.
std::string ros_control_boilerplate::JoystickManualControl::switch_service_ [protected] |
Definition at line 174 of file joystick_manual_control.h.
std::vector<std::string> ros_control_boilerplate::JoystickManualControl::trajectory_controllers_ [protected] |
Definition at line 189 of file joystick_manual_control.h.
Definition at line 185 of file joystick_manual_control.h.