#include <joystick_handler.h>
Public Types | |
typedef boost::shared_ptr < JoystickHandler > | ConstPtr |
typedef boost::shared_ptr < JoystickHandler > | Ptr |
Public Member Functions | |
void | getJoystickCommand (geometry_msgs::Twist &twist, bool &enable) const |
void | joyCallback (const sensor_msgs::Joy::ConstPtr &last_joy_msg) |
JoystickHandler (ros::NodeHandle &nh) | |
virtual | ~JoystickHandler () |
Protected Member Functions | |
double | convertJoyAxisToAcc (double elapsed_time_sec, double joy_val, double val, double min_vel, double max_vel) const |
void | initJoystickInput (XmlRpc::XmlRpcValue ¶ms, std::string name, JoystickInputHandle::Ptr &handle) const |
void | updateJoystickCommand (double elapsed_time_sec, double joy_val, double &val, double min_vel, double max_vel, double min_acc, double max_acc, double sensivity) const |
Protected Attributes | |
JoystickInputHandle::Ptr | enable_ |
bool | has_joy_msg_ |
ros::Subscriber | joy_sub_ |
JoystickInputHandle::Ptr | x_axis_ |
JoystickInputHandle::Ptr | y_axis_ |
JoystickInputHandle::Ptr | yaw_axis_ |
Definition at line 149 of file joystick_handler.h.
typedef boost::shared_ptr<JoystickHandler> vigir_footstep_planning::JoystickHandler::ConstPtr |
Definition at line 161 of file joystick_handler.h.
typedef boost::shared_ptr<JoystickHandler> vigir_footstep_planning::JoystickHandler::Ptr |
Definition at line 160 of file joystick_handler.h.
Definition at line 7 of file joystick_handler.cpp.
Definition at line 25 of file joystick_handler.cpp.
double vigir_footstep_planning::JoystickHandler::convertJoyAxisToAcc | ( | double | elapsed_time_sec, |
double | joy_val, | ||
double | val, | ||
double | min_vel, | ||
double | max_vel | ||
) | const [protected] |
Definition at line 96 of file joystick_handler.cpp.
void vigir_footstep_planning::JoystickHandler::getJoystickCommand | ( | geometry_msgs::Twist & | twist, |
bool & | enable | ||
) | const |
Definition at line 46 of file joystick_handler.cpp.
void vigir_footstep_planning::JoystickHandler::initJoystickInput | ( | XmlRpc::XmlRpcValue & | params, |
std::string | name, | ||
JoystickInputHandle::Ptr & | handle | ||
) | const [protected] |
Definition at line 69 of file joystick_handler.cpp.
void vigir_footstep_planning::JoystickHandler::joyCallback | ( | const sensor_msgs::Joy::ConstPtr & | last_joy_msg | ) |
Definition at line 29 of file joystick_handler.cpp.
void vigir_footstep_planning::JoystickHandler::updateJoystickCommand | ( | double | elapsed_time_sec, |
double | joy_val, | ||
double & | val, | ||
double | min_vel, | ||
double | max_vel, | ||
double | min_acc, | ||
double | max_acc, | ||
double | sensivity | ||
) | const [protected] |
Definition at line 86 of file joystick_handler.cpp.
Definition at line 174 of file joystick_handler.h.
bool vigir_footstep_planning::JoystickHandler::has_joy_msg_ [protected] |
Definition at line 176 of file joystick_handler.h.
Definition at line 179 of file joystick_handler.h.
Definition at line 170 of file joystick_handler.h.
Definition at line 171 of file joystick_handler.h.
Definition at line 172 of file joystick_handler.h.