#include <joystick_handler.h>
|
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 |
|
Definition at line 149 of file joystick_handler.h.
vigir_footstep_planning::JoystickHandler::JoystickHandler |
( |
ros::NodeHandle & |
nh | ) |
|
vigir_footstep_planning::JoystickHandler::~JoystickHandler |
( |
| ) |
|
|
virtual |
double vigir_footstep_planning::JoystickHandler::convertJoyAxisToAcc |
( |
double |
elapsed_time_sec, |
|
|
double |
joy_val, |
|
|
double |
val, |
|
|
double |
min_vel, |
|
|
double |
max_vel |
|
) |
| const |
|
protected |
void vigir_footstep_planning::JoystickHandler::getJoystickCommand |
( |
geometry_msgs::Twist & |
twist, |
|
|
bool & |
enable |
|
) |
| const |
void vigir_footstep_planning::JoystickHandler::joyCallback |
( |
const sensor_msgs::Joy::ConstPtr & |
last_joy_msg | ) |
|
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 |
bool vigir_footstep_planning::JoystickHandler::has_joy_msg_ |
|
protected |
The documentation for this class was generated from the following files: