diff --git a/control/joystick_handler/include/Configuration.h b/control/joystick_handler/include/Configuration.h index 94bb1ad..98ea21d 100644 --- a/control/joystick_handler/include/Configuration.h +++ b/control/joystick_handler/include/Configuration.h @@ -1,4 +1,4 @@ -#define METERS_PER_DEGREE 0.001 //Conversion from motor units to native units -#define TRACK_WIDTH 0.4 //Track width in meters -#define MAX_SPEED 1 //Max speed in meters per second -#define MAX_TURN 1 //Max turn in Radians per second +#define METERS_PER_DEGREE 0.001 //Conversion from motor units to native units +#define TRACK_WIDTH 0.4 //Track width in meters +#define MAX_SPEED 2 //Max speed in meters per second +#define MAX_TURN 2 //Max turn in Radians per second diff --git a/control/joystick_handler/joystick_handler_flight.launch b/control/joystick_handler/joystick_handler_flight.launch new file mode 100644 index 0000000..dabe4a0 --- /dev/null +++ b/control/joystick_handler/joystick_handler_flight.launch @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/control/joystick_handler/joystick_handler_flight_sim.launch b/control/joystick_handler/joystick_handler_flight_sim.launch new file mode 100644 index 0000000..2010319 --- /dev/null +++ b/control/joystick_handler/joystick_handler_flight_sim.launch @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/control/joystick_handler/joystick_handler_flight_simrace.launch b/control/joystick_handler/joystick_handler_flight_simrace.launch new file mode 100644 index 0000000..2010319 --- /dev/null +++ b/control/joystick_handler/joystick_handler_flight_simrace.launch @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/control/joystick_handler/joystick_handler_flight_turtle.launch b/control/joystick_handler/joystick_handler_flight_turtle.launch new file mode 100644 index 0000000..a39bc02 --- /dev/null +++ b/control/joystick_handler/joystick_handler_flight_turtle.launch @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/control/joystick_handler/src/joystick_handler.cpp b/control/joystick_handler/src/joystick_handler.cpp index 74048de..b86251a 100644 --- a/control/joystick_handler/src/joystick_handler.cpp +++ b/control/joystick_handler/src/joystick_handler.cpp @@ -1,7 +1,7 @@ #include #include #include -#include "Configuration.h" +#include "../include/Configuration.h" // #include "joystick/RoboteqCommand.h" // To use: run: @@ -44,7 +44,6 @@ enum joystickInputs // float value[21]; // }; - class JoystickHandler { public: @@ -53,7 +52,7 @@ class JoystickHandler int id; private: - void joyCallback(const sensor_msgs::Joy::ConstPtr& joy); + void joyCallback(const sensor_msgs::Joy::ConstPtr &joy); ros::NodeHandle nh_; @@ -63,13 +62,11 @@ class JoystickHandler double l_scale_, a_scale_; ros::Publisher vel_pub_; ros::Subscriber joy_sub_; - }; // Set-up subscribers/publishers in constructor -JoystickHandler::JoystickHandler(int joynum): - linear_(1), - angular_(1) +JoystickHandler::JoystickHandler(int joynum) : linear_(1), + angular_(1) { nh_.param("axis_linear", linear_, linear_); nh_.param("axis_angular", angular_, angular_); @@ -77,7 +74,7 @@ JoystickHandler::JoystickHandler(int joynum): nh_.param("scale_linear", l_scale_, l_scale_); // Get joystick info from /joy - joy_sub_ = nh_.subscribe("j"+std::to_string(joynum), 10, &JoystickHandler::joyCallback, this); + joy_sub_ = nh_.subscribe("j" + std::to_string(joynum), 10, &JoystickHandler::joyCallback, this); std::string topic_name; nh_.getParam("joy_pub_topic", topic_name); @@ -93,48 +90,48 @@ float JoystickHandler::getValue(joystickInputs i) return values[i]; } -void JoystickHandler::joyCallback(const sensor_msgs::Joy::ConstPtr& joy) +void JoystickHandler::joyCallback(const sensor_msgs::Joy::ConstPtr &joy) { - if(id == 0) + if (id == 0) { std::cout << "\033[1;33m"; } - else if(1) + else if (1) { std::cout << "\033[1;36m"; } - for(int i = 0; i < 8; i++) + for (int i = 0; i < 8; i++) { values[i] = joy->axes[i]; printf("%f ", values[i]); } - for(int i = 0; i < 13; i++) + for (int i = 0; i < 13; i++) { - values[i+8] = joy->buttons[i]; - printf("%i ", (int)values[i+8]); + values[i + 8] = joy->buttons[i]; + printf("%i ", (int)values[i + 8]); } std::cout << "\033[0m\n"; // printf("\n"); geometry_msgs::Twist twist; - twist.angular.z = joy->axes[angular_]; // Set rotation axis data - twist.linear.x = joy->axes[linear_]; // Set forward/backward axis data + twist.angular.z = joy->axes[angular_] * MAX_TURN; // Set rotation axis data + twist.linear.x = joy->axes[linear_] * MAX_SPEED; // Set forward/backward axis data vel_pub_.publish(twist); } -void callback(const geometry_msgs::Twist::ConstPtr& msg){ - double linear = msg->linear.x; - double angular = msg->angular.z; - double leftVelocity; //Velocity 1 - double rightVelocity; //Velocity 2 - leftVelocity = linear - TRACK_WIDTH * angular/2; - rightVelocity = linear + TRACK_WIDTH * angular/2; - - // ROS_INFO("%f, %f", leftVelocity, rightVelocity); +void callback(const geometry_msgs::Twist::ConstPtr &msg) +{ + double linear = msg->linear.x; + double angular = msg->angular.z; + double leftVelocity; //Velocity 1 + double rightVelocity; //Velocity 2 + leftVelocity = linear - TRACK_WIDTH * angular / 2; + rightVelocity = linear + TRACK_WIDTH * angular / 2; + + // ROS_INFO("%f, %f", leftVelocity, rightVelocity); } - -int main(int argc, char** argv) +int main(int argc, char **argv) { ros::init(argc, argv, "joy_handler"); diff --git a/extras/arduino-sample/include/Configuration.h b/extras/arduino-sample/include/Configuration.h deleted file mode 100644 index 94bb1ad..0000000 --- a/extras/arduino-sample/include/Configuration.h +++ /dev/null @@ -1,4 +0,0 @@ -#define METERS_PER_DEGREE 0.001 //Conversion from motor units to native units -#define TRACK_WIDTH 0.4 //Track width in meters -#define MAX_SPEED 1 //Max speed in meters per second -#define MAX_TURN 1 //Max turn in Radians per second diff --git a/extras/arduino-sample/src/joystick_handler.cpp b/extras/arduino-sample/src/joystick_handler.cpp deleted file mode 100644 index 74048de..0000000 --- a/extras/arduino-sample/src/joystick_handler.cpp +++ /dev/null @@ -1,149 +0,0 @@ -#include -#include -#include -#include "Configuration.h" -// #include "joystick/RoboteqCommand.h" - -// To use: run: -// roslaunch turtle_joy.launch - -// Or alternatively: -// rosrun joy joynode with rosrun -// and -// rosrun joystick turtle_teleop_joy - -enum joystickInputs -{ - // Digital - A, - B, - X, - Y, - L1, - R1, - L2, - R2, - Share, - Options, - Home, - L3, - R3, - // Analog - LSX, - LSY, - L2Analog, - RSX, - RSY, - R2Analog, - HatX, - HatY -}; - -// struct joystick_values -// { -// float value[21]; -// }; - - -class JoystickHandler -{ -public: - JoystickHandler(int); - float getValue(joystickInputs); - int id; - -private: - void joyCallback(const sensor_msgs::Joy::ConstPtr& joy); - - ros::NodeHandle nh_; - - float values[21]; - - int linear_, angular_; - double l_scale_, a_scale_; - ros::Publisher vel_pub_; - ros::Subscriber joy_sub_; - -}; - -// Set-up subscribers/publishers in constructor -JoystickHandler::JoystickHandler(int joynum): - linear_(1), - angular_(1) -{ - nh_.param("axis_linear", linear_, linear_); - nh_.param("axis_angular", angular_, angular_); - nh_.param("scale_angular", a_scale_, a_scale_); - nh_.param("scale_linear", l_scale_, l_scale_); - - // Get joystick info from /joy - joy_sub_ = nh_.subscribe("j"+std::to_string(joynum), 10, &JoystickHandler::joyCallback, this); - - std::string topic_name; - nh_.getParam("joy_pub_topic", topic_name); - - // Set joystick values in /cmd_vel - vel_pub_ = nh_.advertise(topic_name, 1); - - id = joynum; -} - -float JoystickHandler::getValue(joystickInputs i) -{ - return values[i]; -} - -void JoystickHandler::joyCallback(const sensor_msgs::Joy::ConstPtr& joy) -{ - if(id == 0) - { - std::cout << "\033[1;33m"; - } - else if(1) - { - std::cout << "\033[1;36m"; - } - for(int i = 0; i < 8; i++) - { - values[i] = joy->axes[i]; - printf("%f ", values[i]); - } - for(int i = 0; i < 13; i++) - { - values[i+8] = joy->buttons[i]; - printf("%i ", (int)values[i+8]); - } - std::cout << "\033[0m\n"; - // printf("\n"); - - geometry_msgs::Twist twist; - twist.angular.z = joy->axes[angular_]; // Set rotation axis data - twist.linear.x = joy->axes[linear_]; // Set forward/backward axis data - vel_pub_.publish(twist); -} - -void callback(const geometry_msgs::Twist::ConstPtr& msg){ - double linear = msg->linear.x; - double angular = msg->angular.z; - double leftVelocity; //Velocity 1 - double rightVelocity; //Velocity 2 - leftVelocity = linear - TRACK_WIDTH * angular/2; - rightVelocity = linear + TRACK_WIDTH * angular/2; - - // ROS_INFO("%f, %f", leftVelocity, rightVelocity); -} - - -int main(int argc, char** argv) -{ - ros::init(argc, argv, "joy_handler"); - - JoystickHandler joy_handler(0); - JoystickHandler joy_handler1(1); - - // Handler for setting calcualted velocity values - // ros::NodeHandle vel_handle; - // ros::Subscriber vel_sub = vel_handle.subscribe("/cmd_vel", 1000, callback); - - ros::spin(); -} diff --git a/extras/etc/udev/rules.d/10-sdrcJoystick.rules b/extras/etc/udev/rules.d/10-sdrcJoystick.rules index 565804d..ded8c6e 100644 --- a/extras/etc/udev/rules.d/10-sdrcJoystick.rules +++ b/extras/etc/udev/rules.d/10-sdrcJoystick.rules @@ -38,6 +38,13 @@ ACTION=="add" \ , ATTRS{idVendor}=="054c" \ , SYMLINK+="SDRCDualshock4" +# Logitech Extreme 3D Pro Flight Joystick to dev/SDRCFlightJoystick +ACTION=="add" \ +, KERNEL=="js*" \ +, ATTRS{idProduct}=="c215" \ +, ATTRS{idVendor}=="046d" \ +, SYMLINK+="SDRCFlightJoystick" + # Arduino UNO Green ACTION=="add" \ , ATTRS{serial}=="5563931343335131F002" \