#include <ManControl.hpp>
Public Member Functions | |
JoystickMapping () | |
void | remap (const sensor_msgs::Joy &joy, Eigen::Vector6d &mapped) |
Private Attributes | |
Eigen::Vector6i | axes_map |
Eigen::Vector6d | scale_map |
The class performs joystick mappings from received axes to regular tau axes. Tau axes are defined as (X,Y,Z,K,M,N). Joystick axes are defined as: (1-n) where n is the maximum axis number. The mapping is a row vector (1x6) (joystick_mapping/axes_map) that has the desired axis defined in the according place of the tau axis. For disabled axis define the axis number -1. The scaling is defined in (joystick_mapping/scale_map) as a desired double number.
Definition at line 67 of file ManControl.hpp.
labust::control::JoystickMapping::JoystickMapping | ( | ) | [inline] |
Main constructor.
Definition at line 73 of file ManControl.hpp.
void labust::control::JoystickMapping::remap | ( | const sensor_msgs::Joy & | joy, |
Eigen::Vector6d & | mapped | ||
) | [inline] |
Definition at line 93 of file ManControl.hpp.
Definition at line 106 of file ManControl.hpp.
Definition at line 107 of file ManControl.hpp.