[PATCH] adaptation of the component for the new controldev library using vector with names Joystick works as 1D array of named vector using base types. 1D facilitates potential complex maneuver to command with a joystick with multiple sub-joystick/ It avoids sub-indexes with the need of two variables Mouse3d, Remote, SteeringWheel and Sliderbox tasks have been adapted but not tested.

Javier Hidalgo Carrio javier.hidalgo_carrio at dfki.de
Thu Apr 10 11:49:56 CEST 2014


---
 ControlDevTypes.hpp         |   20 +++---
 controldev.orogen           |    1 -
 tasks/GenericTask.cpp       |   10 +--
 tasks/JoystickTask.cpp      |  154 ++++++++++++++++++++++++++-----------------
 tasks/JoystickTask.hpp      |    6 +-
 tasks/Mouse3DTask.cpp       |   19 +++---
 tasks/Remote.cpp            |   42 ++++++------
 tasks/SliderboxTask.cpp     |    7 +-
 tasks/SteeringWheelTask.cpp |   21 +++---
 9 files changed, 152 insertions(+), 128 deletions(-)

diff --git a/ControlDevTypes.hpp b/ControlDevTypes.hpp
index 8c69347..e73da70 100644
--- a/ControlDevTypes.hpp
+++ b/ControlDevTypes.hpp
@@ -2,6 +2,7 @@
 #define CONTROLDEVTYPES_HPP
 
 #include <base/actuators/commands.h>
+#include <base/NamedVector.hpp>
 
 namespace controldev
 {
@@ -35,24 +36,21 @@ namespace controldev
 	std::string deviceIdentifier;
 
         /*
-         * The Timesamp
+         * The time stamp
          */
         base::Time time;
 
-        /* Index 1: num-of input axis, //index 2: dimensions of this axis
-         * If you have an gamepand which has 2 2Dknops you have an [2][2] 
-         * size'd array for an 3D Mouse you could have [1][6]
-         */
-        std::vector<std::vector<double> > axisValue;
+        /* Named vector for the axis */
+        base::NamedVector <double> axes;
 
         /*
-         * Switch/Key Values
+         * Named vector Switch/Key Values
          * Three State switches are handles as two
-         * Comment, this has to be handeld as an bool vecotr.
-         * Sine bools are buggy in rock currently, workaround it with an uint8_t
-         * vecotr. For more details see http://rock.opendfki.de/ticket/187
+         * Comment, this has to be handle as an boolean vector.
+         * Sine boolean are buggy in rock currently, workaround it with an uint8_t
+         * vector. For more details see http://rock.opendfki.de/ticket/187
          */
-        std::vector<uint8_t> buttonValue;
+        base::NamedVector <int> buttons;
     };
 
     /** Data structure to send separate commands for each motor */
diff --git a/controldev.orogen b/controldev.orogen
index ab83a73..225e8a4 100644
--- a/controldev.orogen
+++ b/controldev.orogen
@@ -50,7 +50,6 @@ task_context "JoystickTask" do
     property("device", "/std/string", "/dev/input/js0").
         doc("Path to the joystick device")
 
-    property("axisScaling","/std/vector<double>")
 end
 
 task_context "Mouse3DTask" do
diff --git a/tasks/GenericTask.cpp b/tasks/GenericTask.cpp
index 6922860..aa4e7fe 100644
--- a/tasks/GenericTask.cpp
+++ b/tasks/GenericTask.cpp
@@ -42,7 +42,7 @@ bool GenericTask::mapFromSliderbox(FourWheelCommand& cmd, RawCommand const& inpu
 	for (int i = 0; i < 7; i++)
 	{
 		// Reads the slider value from MIN to MAX and scales it to 0 to 1
-		sliderValues[i] = (( input.axisValue[0][i]- SLIDER_MIN) / (SLIDER_MAX-SLIDER_MIN));
+		sliderValues[i] = (( input.axes.elements[i]- SLIDER_MIN) / (SLIDER_MAX-SLIDER_MIN));
 
 		// Rounds the data outside MIN and MAX
 		if (sliderValues[i] > 1.0)
@@ -52,7 +52,7 @@ bool GenericTask::mapFromSliderbox(FourWheelCommand& cmd, RawCommand const& inpu
 	}
 
 	/* OFF state */	
-	if (! input.buttonValue[3] )/* Button 4 */
+	if (! input.buttons.elements[3] )/* Button 4 */
 	{
 		cmd = FourWheelCommand();
 		return true;
@@ -64,7 +64,7 @@ bool GenericTask::mapFromSliderbox(FourWheelCommand& cmd, RawCommand const& inpu
 	for (int i=0;i<4;i++)
 	{
 		// Sets the mode based on status of Button 3
-		if (input.buttonValue[2])  /* Button 3 */
+		if (input.buttons.elements[2])  /* Button 3 */
 		{
 			/* PWM Mode */
 			cmd.mode[i] = base::actuators::DM_PWM;
@@ -81,7 +81,7 @@ bool GenericTask::mapFromSliderbox(FourWheelCommand& cmd, RawCommand const& inpu
 	/* Sets the driving mode and calulates the individual velocities*/
 
 	/* Individual wheel and Master wheel set drive */
-	if (input.buttonValue[1])   /* Button 2 */
+	if (input.buttons.elements[1])   /* Button 2 */
 	{
 
 		cmd.target[3] = 2  * (sliderValues[SLIDER_MASTER_VEL_LEFT]  - 0.5) 
@@ -137,7 +137,7 @@ bool GenericTask::mapFromSliderbox(FourWheelCommand& cmd, RawCommand const& inpu
 	}
 
 
-	if (input.buttonValue[0])   /* Button 1 */
+	if (input.buttons.elements[0])   /* Button 1 */
 	    cmd.sync = true;
 	else 
 	    cmd.sync = false;
diff --git a/tasks/JoystickTask.cpp b/tasks/JoystickTask.cpp
index e955255..b0eedd4 100644
--- a/tasks/JoystickTask.cpp
+++ b/tasks/JoystickTask.cpp
@@ -2,6 +2,7 @@
 
 #include "JoystickTask.hpp"
 #include <controldev/Joystick.hpp>
+#include <controldev/EvdevHelper.hpp>
 #include <rtt/extras/FileDescriptorActivity.hpp>
 
 using namespace controldev;
@@ -9,12 +10,6 @@ using namespace controldev;
 JoystickTask::JoystickTask(std::string const& name)
     : JoystickTaskBase(name), joystick(new controldev::Joystick())
 {
-    std::vector<double> v= _axisScale.get();
-    v.resize(4);
-    for(int i=0;i<4;i++){
-        v[i] = 1.0; 
-    }
-    _axisScale.set(v);
 }
 
 JoystickTask::JoystickTask(std::string const& name, RTT::ExecutionEngine* engine)
@@ -35,7 +30,7 @@ bool JoystickTask::configureHook()
 {
     if (! JoystickTaskBase::configureHook())
         return false;
-    
+
     // Try to connect the Joystick
     if (!joystick->init(_device.value()))
     {
@@ -44,6 +39,15 @@ bool JoystickTask::configureHook()
 	return false;
     }
 
+
+    /** Joystick information **/
+    this->axisCount = joystick->getNrAxis();
+    this->buttonCount = joystick->getNrButtons();
+
+    /** Get the configuration information. It requires a proper configuration **/
+    this->axisScale = _axisScale.get();
+    assert(axisScale.size() == static_cast<unsigned int> (this->axisCount));
+
     return true;
 }
 
@@ -51,94 +55,120 @@ bool JoystickTask::startHook()
 {
     if (! JoystickTaskBase::startHook())
         return false;
-    
+
     RTT::extras::FileDescriptorActivity* activity =
         getActivity<RTT::extras::FileDescriptorActivity>();
     if (activity)
     {
 	activity->watch(joystick->getFileDescriptor());
     }
-    
+
     return true;
 }
 
+void JoystickTask::updateHook()
+{
+    JoystickTaskBase::updateHook();
+
+    RawCommand rcmd;
+
+    if (!updateRawCommand(rcmd)) return;
+
+    sendMotionCommand2D(rcmd);
 
+}
+
+void JoystickTask::stopHook()
+{
+    RTT::extras::FileDescriptorActivity* activity =
+        getActivity<RTT::extras::FileDescriptorActivity>();
+    if(activity)
+        activity->clearAllWatches();
+
+    JoystickTaskBase::stopHook();
+}
 bool JoystickTask::updateRawCommand(RawCommand& rcmd) {
 
-    assert(_axisScale.get().size() == 4);
     bool update = false;
-    // New data available at the Joystick device
+
+    /** New data available at the Joystick device **/
     while(this->joystick->updateState())
     {
 	update = true;
     }
-    
-//    if(!update)
-//	return false;
-    
+
+    /** Device name **/
     rcmd.deviceIdentifier= this->joystick->getName();
-    
-    std::vector<double> axis;
-    axis.push_back(this->joystick->getAxis(Joystick::AXIS_Forward)*_axisScale.get()[0]);
-    axis.push_back(this->joystick->getAxis(Joystick::AXIS_Sideward)*_axisScale.get()[1]);
-    axis.push_back(this->joystick->getAxis(Joystick::AXIS_Turn)*_axisScale.get()[2]);
-    
-    std::vector<double> axis2;
-    axis2.push_back(this->joystick->getAxis(Joystick::AXIS_Slider)*_axisScale.get()[3]);
-    rcmd.axisValue.push_back(axis);
-    rcmd.axisValue.push_back(axis2);
-    
-    int buttonCount = this->joystick->getNrButtons();
-
-    // Set button bit list
-    for (int i = 0; i < buttonCount; i++)
+
+    /** Axis mapping **/
+    rcmd.axes.names = this->joystick->getMapAxis();
+    register size_t l = 0;
+    std::vector<double> axes_value = this->joystick->getAxes();
+    for(std::vector<double>::iterator it=axes_value.begin(); it!=axes_value.end(); ++it)
+    {
+        rcmd.axes.elements.push_back((*it)*axisScale[l]);
+        l++;
+    }
+
+    /** Buttons mapping **/
+    rcmd.buttons.names = this->joystick->getMapButtons();
+    std::vector<bool> buttons_value = this->joystick->getButtons();
+    for(std::vector<bool>::iterator it=buttons_value.begin(); it!=buttons_value.end(); ++it)
     {
-        rcmd.buttonValue.push_back(this->joystick->getButtonPressed(i));
+        rcmd.buttons.elements.push_back(static_cast<int>(*it));
     }
-    
+
+    /** Time stamp **/
+    rcmd.time = base::Time::now();
+
+    /** Write in the port **/
     _raw_command.write(rcmd);
 
-    return true;
+    return update;
 }
 
-void JoystickTask::sendMotionCommand2D(const RawCommand& rcmd) {
+/** This is a simple/generic 2D command generator each subclass should have its own one **/
+void JoystickTask::sendMotionCommand2D(const RawCommand& rcmd)
+{
     base::MotionCommand2D mcmd;
-    if(rcmd.axisValue.size() != 2) return;
-    if(rcmd.axisValue[0].size() != 3) return;
-    if(rcmd.axisValue[1].size() != 1) return;
 
+    /** At least two axes to command a 2D motion **/
+    if(rcmd.axes.size() < 2) return;
+
+    /** Configuration values **/
     float max_speed = _maxSpeed.get();
     float min_speed = _minSpeed.get();
-    float max_speed_ratio = (rcmd.axisValue[1][0] * min_speed) / (1.0 + min_speed);
     float max_rotation_speed = _maxRotationSpeed.get();
-    double x = rcmd.axisValue[0][0] * max_speed * max_speed_ratio;
-    double y = rcmd.axisValue[0][1];
-    
-    mcmd.rotation    = -fabs(y) * atan2(y, fabs(x)) / M_PI * max_rotation_speed;
-    mcmd.translation = x;
-    
-    // Send motion command
-    _motion_command.write(mcmd);
-}
 
-void JoystickTask::updateHook()
-{
-    JoystickTaskBase::updateHook();
-     
-    RawCommand rcmd;
+    /** Speed ratio only it has a throttle absolute axis (ABS)**/
+    float max_speed_ratio;
+    try
+    {
+        /** In linux/input.h and used by the controldev library defines the ABS_THROTTLE **/
+        double throttle = rcmd.axes[abs2str(6)];
 
-    if (!updateRawCommand(rcmd)) return;
+        /** Throttle between 0  and 1**/
+        max_speed_ratio = 0.5 + (throttle/2.0);
 
-    sendMotionCommand2D(rcmd);
+       //What was max_speed ratio before ??
+       // max_speed_ratio = (rcmd.axes[abs2str(6)] * min_speed) / (1.0 + min_speed);
+    }
+    catch (const std::runtime_error& error)
+    {
+        /** TO-DO: perhaps write in the RTT log that there is not a throttle axis **/
+        max_speed_ratio = 1.0;
+    }
 
-}
+    /** Get the x-y information. TO-DO: it could also be accessed by name **/
+    double x = rcmd.axes[1] * max_speed * max_speed_ratio;
+    double y = rcmd.axes[0];
 
-void JoystickTask::stopHook()
-{
-    RTT::extras::FileDescriptorActivity* activity =
-        getActivity<RTT::extras::FileDescriptorActivity>();
-    if(activity)
-        activity->clearAllWatches();
+    /** Calculate the 2D command **/
+    mcmd.rotation    = -fabs(y) * atan2(y, fabs(x)) / M_PI * max_rotation_speed;
+    mcmd.translation = x;
 
-    JoystickTaskBase::stopHook();
+    /** Send motion command **/
+    _motion_command.write(mcmd);
 }
+
+
diff --git a/tasks/JoystickTask.hpp b/tasks/JoystickTask.hpp
index 3602f0b..6ef9eca 100644
--- a/tasks/JoystickTask.hpp
+++ b/tasks/JoystickTask.hpp
@@ -7,12 +7,16 @@
 
 namespace controldev {
     class Joystick;
-    
+
     class JoystickTask : public JoystickTaskBase
     {
 	friend class JoystickTaskBase;
     protected:
         Joystick *joystick;
+        int buttonCount, axisCount;
+
+        /** Configuration values **/
+        std::vector<double>axisScale;
 
         virtual bool updateRawCommand(RawCommand& rcmd);
         void sendMotionCommand2D(const RawCommand& rcmd);
diff --git a/tasks/Mouse3DTask.cpp b/tasks/Mouse3DTask.cpp
index f3e76bd..e535575 100644
--- a/tasks/Mouse3DTask.cpp
+++ b/tasks/Mouse3DTask.cpp
@@ -93,21 +93,20 @@ void Mouse3DTask::updateHook()
     RawCommand rcmd;
     rcmd.deviceIdentifier= "3DMouse";
    
-    rcmd.axisValue.resize(1);
-    rcmd.axisValue[0].resize(6);
+    rcmd.axes.elements.resize(6);
    
     connexionValues values;
     connexionValues rawValues;
     interface->getValue(values,rawValues);
 
-    rcmd.axisValue[0][0] = values.tx;
-    rcmd.axisValue[0][1] = values.ty;
-    rcmd.axisValue[0][2] = values.tz;
-    rcmd.axisValue[0][3] = values.rx;
-    rcmd.axisValue[0][4] = values.ry;
-    rcmd.axisValue[0][5] = values.rz;
-    rcmd.buttonValue.push_back(values.button1);
-    rcmd.buttonValue.push_back(values.button2);
+    rcmd.axes.elements[0] = values.tx;
+    rcmd.axes.elements[1] = values.ty;
+    rcmd.axes.elements[2] = values.tz;
+    rcmd.axes.elements[3] = values.rx;
+    rcmd.axes.elements[4] = values.ry;
+    rcmd.axes.elements[5] = values.rz;
+    rcmd.buttons.elements.push_back(values.button1);
+    rcmd.buttons.elements.push_back(values.button2);
     _raw_command.write(rcmd);
 }
 
diff --git a/tasks/Remote.cpp b/tasks/Remote.cpp
index deaa387..79b9022 100644
--- a/tasks/Remote.cpp
+++ b/tasks/Remote.cpp
@@ -38,29 +38,26 @@ void Remote::updateHook()
 
         rcmd.deviceIdentifier = "CAN-Joystick";
 
-        rcmd.axisValue.resize(3);
-        rcmd.axisValue[0].resize(3);
-        rcmd.axisValue[1].resize(1);
-        rcmd.axisValue[2].resize(2);
-
-        rcmd.axisValue[0][1]    = ((char)msg.data[0]) / 127.0;
-        rcmd.axisValue[0][0]    = ((char)msg.data[1]) / 127.0;
-        rcmd.axisValue[0][2]    = ((char)msg.data[2]) / 127.0;
-        rcmd.axisValue[1][0]    = -((char)msg.data[3]) / 127.0;
-        rcmd.axisValue[2][0]    = ((char)msg.data[4]) / 127.0;
-        rcmd.axisValue[2][1]    = ((char)msg.data[5]) / 127.0;
+        rcmd.axes.elements.resize(6);
+
+        rcmd.axes.elements[0]    = ((char)msg.data[0]) / 127.0;
+        rcmd.axes.elements[1]    = ((char)msg.data[1]) / 127.0;
+        rcmd.axes.elements[2]    = ((char)msg.data[2]) / 127.0;
+        rcmd.axes.elements[3]    = -((char)msg.data[3]) / 127.0;
+        rcmd.axes.elements[4]    = ((char)msg.data[4]) / 127.0;
+        rcmd.axes.elements[5]    = ((char)msg.data[5]) / 127.0;
         for(int i=0;i<8;i++){
-            rcmd.buttonValue.push_back(msg.data[6] &(1<<i));
+            rcmd.buttons.elements.push_back(msg.data[6] &(1<<i));
         }
 
         // [ticks/ms]
         float max_speed = _maxSpeed.get();
         float min_speed = _minSpeed.get();
-        float max_speed_ratio = (rcmd.axisValue[1][0] + min_speed) / (1.0 + min_speed);
+        float max_speed_ratio = (rcmd.axes.elements[3] + min_speed) / (1.0 + min_speed);
         float max_rotation_speed = _maxRotationSpeed.get();
-        double x = rcmd.axisValue[0][0]   * max_speed * max_speed_ratio;
-        double y = rcmd.axisValue[0][1];
-        
+        double x = rcmd.axes.elements[1]   * max_speed * max_speed_ratio;
+        double y = rcmd.axes.elements[0];
+
         mcmd.rotation    = -fabs(y) * atan2(y, fabs(x)) / M_PI * max_rotation_speed;
         mcmd.translation = x;
 
@@ -70,27 +67,26 @@ void Remote::updateHook()
     {
         // Send motion command
         _motion_command.write(mcmd);
-        
+
         // Send raw command
         _raw_command.write(rcmd);
     }
 
     while (_canSliderBox.read(msg) == RTT::NewData)
     {
-        rcmd.axisValue.clear();
-        rcmd.buttonValue.clear();
+        rcmd.axes.elements.clear();
+        rcmd.buttons.elements.clear();
 
-        rcmd.axisValue.push_back(std::vector<double>());
-        rcmd.axisValue[0].resize(6);
+        rcmd.axes.elements.resize(6);
         rcmd.deviceIdentifier = "CAN-Sliderbox";
 
         for (int i = 0; i < 7; i++)
         {
-            rcmd.axisValue[0][i] = msg.data[i];
+            rcmd.axes.elements[i] = msg.data[i];
         }
 
         for(int i=0;i<8;i++){
-            rcmd.buttonValue.push_back(msg.data[7] &(1<<i));
+            rcmd.buttons.elements.push_back(msg.data[7] &(1<<i));
         }
 
         FourWheelCommand wheel_command;
diff --git a/tasks/SliderboxTask.cpp b/tasks/SliderboxTask.cpp
index 4e4a3b7..502a2f7 100644
--- a/tasks/SliderboxTask.cpp
+++ b/tasks/SliderboxTask.cpp
@@ -76,17 +76,16 @@ void SliderboxTask::updateHook()
     
     rcmd.deviceIdentifier = "Sliderbox";
 
-    rcmd.axisValue.resize(1);
-    rcmd.axisValue[0].resize(6);
+    rcmd.axes.elements.resize(6);
     
     for (int i = 0; i < 7; i++)
     {
-	rcmd.axisValue[0][i] = this->sliderBox->getValue(i);
+	rcmd.axes.elements[i] = this->sliderBox->getValue(i);
     }
 
     for (int i = 0; i < 4; i++)
     {
-        rcmd.buttonValue.push_back(this->sliderBox->getButtonOn(i));
+        rcmd.buttons.elements.push_back(this->sliderBox->getButtonOn(i));
     }
 
     _raw_command.write(rcmd);
diff --git a/tasks/SteeringWheelTask.cpp b/tasks/SteeringWheelTask.cpp
index 0bf5087..20ab853 100644
--- a/tasks/SteeringWheelTask.cpp
+++ b/tasks/SteeringWheelTask.cpp
@@ -78,21 +78,20 @@ void SteeringWheelTask::updateHook()
 
     rcmd.deviceIdentifier = steerControl->getName();
 
-    rcmd.axisValue.resize(1);
-    rcmd.axisValue[0].resize(5);
+    rcmd.axes.elements.resize(5);
 
-    rcmd.axisValue[0][1] = steerControl->getAxis(LogitechG27::AXIS_Wheel);
-    rcmd.axisValue[0][0] = steerControl->getAxis(LogitechG27::AXIS_Clutchdirupdown);
-    rcmd.axisValue[0][2] = steerControl->getAxis(LogitechG27::AXIS_Clutchdirleftright); 
-    rcmd.axisValue[0][3] = steerControl->getAxis(LogitechG27::AXIS_Throttle);
-    rcmd.axisValue[0][4] = steerControl->getAxis(LogitechG27::AXIS_Brake);
+    rcmd.axes.elements[1] = steerControl->getAxis(LogitechG27::AXIS_Wheel);
+    rcmd.axes.elements[0] = steerControl->getAxis(LogitechG27::AXIS_Clutchdirupdown);
+    rcmd.axes.elements[2] = steerControl->getAxis(LogitechG27::AXIS_Clutchdirleftright); 
+    rcmd.axes.elements[3] = steerControl->getAxis(LogitechG27::AXIS_Throttle);
+    rcmd.axes.elements[4] = steerControl->getAxis(LogitechG27::AXIS_Brake);
 
     float max_speed = _maxSpeed.get();
     float min_speed = _minSpeed.get();
-    float max_speed_ratio = (rcmd.axisValue[0][3] + min_speed) / (1.0 + min_speed);
+    float max_speed_ratio = (rcmd.axes.elements[3] + min_speed) / (1.0 + min_speed);
     float max_rotation_speed = _maxRotationSpeed.get();
-    double x = rcmd.axisValue[0][3]  * max_speed;
-    double y = rcmd.axisValue[0][1];
+    double x = rcmd.axes.elements[3]  * max_speed;
+    double y = rcmd.axes.elements[1];
 
     mcmd.rotation = y;
     mcmd.translation = x;
@@ -105,7 +104,7 @@ void SteeringWheelTask::updateHook()
     // Set button bit list
     for (int i = 0; i < buttonCount; i++)
     {
-        rcmd.buttonValue.push_back(steerControl->getButtonPressed(i));
+        rcmd.buttons.elements.push_back(steerControl->getButtonPressed(i));
     }
     
     // Send raw command
-- 
1.7.9.5


--------------080302080400070300080300
Content-Type: application/x-yaml;
 name="controldev::JoystickTask.yml"
Content-Transfer-Encoding: base64
Content-Disposition: attachment;
 filename="controldev::JoystickTask.yml"

LS0tIG5hbWU6ZGVmYXVsdAojIFBhdGggdG8gdGhlIGpveXN0aWNrIGRldmljZQpkZXZpY2U6
IC9kZXYvaW5wdXQvanMwCiMgTWF4aW11bSByb3RhdGlvbiBzcGVlZCBpbiByYWQvcwptYXhS
b3RhdGlvblNwZWVkOiAzLjE0MTU5MjY1MzU4OTc5MwojIE1pbmltdW0gcm90YXRpb24gc3Bl
ZWQgaW4gcmFkL3MKbWluUm90YXRpb25TcGVlZDogLTMuMTQxNTkyNjUzNTg5NzkzCgojIE1h
eGltdW0gdHJhbnNsYXRpb24gc3BlZWQgaW4gbS9zCm1heFNwZWVkOiAxLjAKIyBNaW5pbXVt
IHRyYW5zbGF0aW9uIHNwZWVkIGluIG0vcwptaW5TcGVlZDogMS4wCiMgbm8gZG9jdW1lbnRh
dGlvbiBhdmFpbGFibGUgZm9yIHRoaXMgcHJvcGVydHkKbWV0YWRhdGE6CiAgbWV0YWRhdGE6
IFtdCiAgcHJvcGVydGllczogW10KICBpbnB1dF9wb3J0czogW10KICBvdXRwdXRfcG9ydHM6
IFtdCgotLS0gbmFtZTp0aHJ1c3RtYXN0ZXIKIyBubyBkb2N1bWVudGF0aW9uIGF2YWlsYWJs
ZSBmb3IgdGhpcyBwcm9wZXJ0eQpheGlzU2NhbGU6IFsxLjAsIDEuMCwgMS4wLCAtMS4wLCAx
LjAsIDEuMF0KCi0tLSBuYW1lOmxvZ2l0ZWNoX2F0dGFjazMKIyBubyBkb2N1bWVudGF0aW9u
IGF2YWlsYWJsZSBmb3IgdGhpcyBwcm9wZXJ0eQpheGlzU2NhbGU6IFsxLjAsIDEuMCwgLTEu
MF0KCi0tLSBuYW1lOnByZWRhdG9yX3RydXN0CiMgbm8gZG9jdW1lbnRhdGlvbiBhdmFpbGFi
bGUgZm9yIHRoaXMgcHJvcGVydHkKYXhpc1NjYWxlOiBbMS4wLCAxLjAsIDAuMCwgLTEuMCwg
MS4wLCAtMS4wLCAtMS4wXQoK
--------------080302080400070300080300
Content-Type: application/x-ruby;
 name="joystick.rb"
Content-Transfer-Encoding: base64
Content-Disposition: attachment;
 filename="joystick.rb"
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--------------080302080400070300080300--


More information about the Rock-dev mailing list