Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
vigir_footstep_planning::JoystickHandler Class Reference

#include <joystick_handler.h>

List of all members.

Public Types

typedef boost::shared_ptr
< JoystickHandler
ConstPtr
typedef boost::shared_ptr
< JoystickHandler
Ptr

Public Member Functions

void joyCallback (const sensor_msgs::Joy::ConstPtr &last_joy_msg)
 JoystickHandler (ros::NodeHandle &nh)
void updateJoystickCommands (double elapsed_time_sec, bool &enable, double &d_x, double &d_y, double &d_yaw) const
virtual ~JoystickHandler ()

Protected Member Functions

double convertJoyAxisToAcc (double elapsed_time_sec, double joy_val, double val, double min_vel, double max_vel) 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

bool enable_generator
ros::Subscriber joy_sub
sensor_msgs::Joy::ConstPtr last_joy_msg
geometry_msgs::Point limits_max_lin_acc
geometry_msgs::Point limits_max_lin_vel
geometry_msgs::Point limits_max_rot_acc
geometry_msgs::Point limits_max_rot_vel
geometry_msgs::Point limits_min_lin_acc
geometry_msgs::Point limits_min_lin_vel
geometry_msgs::Point limits_min_rot_acc
geometry_msgs::Point limits_min_rot_vel
geometry_msgs::Point sensivity_lin
geometry_msgs::Point sensivity_rot
geometry_msgs::Point thresh_lin
geometry_msgs::Point thresh_rot

Detailed Description

Definition at line 42 of file joystick_handler.h.


Member Typedef Documentation

Definition at line 54 of file joystick_handler.h.

Definition at line 53 of file joystick_handler.h.


Constructor & Destructor Documentation

Definition at line 5 of file joystick_handler.cpp.

Definition at line 37 of file joystick_handler.cpp.


Member Function Documentation

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 106 of file joystick_handler.cpp.

void vigir_footstep_planning::JoystickHandler::joyCallback ( const sensor_msgs::Joy::ConstPtr &  last_joy_msg)

Definition at line 41 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 95 of file joystick_handler.cpp.

void vigir_footstep_planning::JoystickHandler::updateJoystickCommands ( double  elapsed_time_sec,
bool &  enable,
double &  d_x,
double &  d_y,
double &  d_yaw 
) const

Definition at line 58 of file joystick_handler.cpp.


Member Data Documentation

Definition at line 79 of file joystick_handler.h.

Definition at line 61 of file joystick_handler.h.

sensor_msgs::Joy::ConstPtr vigir_footstep_planning::JoystickHandler::last_joy_msg [protected]

Definition at line 78 of file joystick_handler.h.

Definition at line 71 of file joystick_handler.h.

Definition at line 69 of file joystick_handler.h.

Definition at line 75 of file joystick_handler.h.

Definition at line 73 of file joystick_handler.h.

Definition at line 70 of file joystick_handler.h.

Definition at line 68 of file joystick_handler.h.

Definition at line 74 of file joystick_handler.h.

Definition at line 72 of file joystick_handler.h.

Definition at line 66 of file joystick_handler.h.

Definition at line 67 of file joystick_handler.h.

geometry_msgs::Point vigir_footstep_planning::JoystickHandler::thresh_lin [protected]

Definition at line 64 of file joystick_handler.h.

geometry_msgs::Point vigir_footstep_planning::JoystickHandler::thresh_rot [protected]

Definition at line 65 of file joystick_handler.h.


The documentation for this class was generated from the following files:


vigir_pattern_generator
Author(s): Alexander Stumpf
autogenerated on Fri Apr 7 2017 02:59:51