00001
00002
00003
00004
00005
00006
00007
00008 #include <telekyb_joystick/JoystickOptions.hpp>
00009
00010 namespace TELEKYB_NAMESPACE
00011 {
00012
00013
00014
00015 JoystickOptions::JoystickOptions()
00016 : OptionContainer("JoystickOptions")
00017 {
00018 tDevicePath = addOption<std::string>("tDevicePath",
00019 "Device Path of Joystick",
00020 "/dev/input/js0", false, true);
00021 tDeadZone = addBoundsOption<double>("tDeadZone",
00022 "Amount by which the joystick has to move before it is considered to be off-center",
00023 0.05, -1.0, 1.0, false, false);
00024 tAutoRepeatRate = addOption<double>("tAutoRepeatRate",
00025 "Rate in Hz at which a joystick that has a non-changing state will resend the previously sent message",
00026 0.0 , false, false);
00027 tCoalesceInterval = addOption<double>("tCoalesceInterval",
00028 "Axis events that are received within coalesce_interval (seconds) of each other are sent out in a single ROS message",
00029 0.001 , false, false);
00030 tPubName = addOption<std::string>("tPubName",
00031 "TopicName that get's added to NodeHandle",
00032 "joy", false, true);
00033 tButtonRemapping = addOption<std::vector<int> >("tButtonRemapping",
00034 "Button Remapping e.g. [1,0,3,3] switches 1 and 0 and maps 3 to 3 AND 4",
00035 std::vector<int>(), false, true);
00036 tAxesRemapping = addOption<std::vector<int> >("tAxesRemapping",
00037 "Axes Remapping e.g. [1,0,3,3] switches 1 and 0 and maps 3 to 3 AND 4",
00038 std::vector<int>(), false, true);
00039 tAxisMultiplier = addOption<std::vector<double> >("tAxisMultiplier",
00040 "Axes Value Multiplication e.g. [-1.0,0.0,0.5] inverts 0, set 1 to 0 scales 2",
00041 std::vector<double>(), false, true);
00042 tPublishVector3 = addOption< bool >("tPublishVector3",
00043 "Publish geometry_msgs::Vector3Stamped of first 3 axes [x,y,z] to tPubName_vector3",
00044 false, false, true);
00045 }
00046
00047 }