Skip to content

Brandon/add flightjoy #56

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 2 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions control/joystick_handler/include/Configuration.h
Original file line number Diff line number Diff line change
@@ -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
29 changes: 29 additions & 0 deletions control/joystick_handler/joystick_handler_flight.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<launch>
<!-- Turtlesim Node-->
<!-- <node pkg="turtlesim" type="turtlesim_node" name="sim"/> -->

<!-- joy node -->
<group>
<remap from='joy' to='j0'/>
<node pkg='joy' name='j0' type='joy_node'>
<param name='dev' type='string' value='/dev/SDRCFlightJoystick'/>
</node>
</group>

<!-- <group>
<remap from='joy' to='joy1'/>
<node pkg='joy' name='joy1' type='joy_node'>
<param name='dev' type='string' value='/dev/input/js1'/>
</node>
</group> -->

<!-- Axes -->
<param name="axis_linear" value="1" type="int"/>
<param name="axis_angular" value="0" type="int"/>
<param name="scale_linear" value="2" type="double"/>
<param name="scale_angular" value="2" type="double"/>
<param name='joy_pub_topic' type='string' value='chassis/cmd_vel'/>

<!-- NOTE: pgk and type do not have to match-->
<node pkg="joystick_handler" type="joystick_handler" name="teleop" output="screen"/>
</launch>
29 changes: 29 additions & 0 deletions control/joystick_handler/joystick_handler_flight_sim.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<launch>
<!-- Turtlesim Node-->
<!-- <node pkg="turtlesim" type="turtlesim_node" name="sim"/> -->

<!-- joy node -->
<group>
<remap from='joy' to='j0'/>
<node pkg='joy' name='j0' type='joy_node'>
<param name='dev' type='string' value='/dev/SDRCFlightJoystick'/>
</node>
</group>

<!-- <group>
<remap from='joy' to='joy1'/>
<node pkg='joy' name='joy1' type='joy_node'>
<param name='dev' type='string' value='/dev/input/js1'/>
</node>
</group> -->

<!-- Axes -->
<param name="axis_linear" value="1" type="int"/>
<param name="axis_angular" value="0" type="int"/>
<param name="scale_linear" value="2" type="double"/>
<param name="scale_angular" value="2" type="double"/>
<param name='joy_pub_topic' type='string' value='/cmd_vel'/>

<!-- NOTE: pgk and type do not have to match-->
<node pkg="joystick_handler" type="joystick_handler" name="teleop" output="screen"/>
</launch>
29 changes: 29 additions & 0 deletions control/joystick_handler/joystick_handler_flight_simrace.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<launch>
<!-- Turtlesim Node-->
<!-- <node pkg="turtlesim" type="turtlesim_node" name="sim"/> -->

<!-- joy node -->
<group>
<remap from='joy' to='j0'/>
<node pkg='joy' name='j0' type='joy_node'>
<param name='dev' type='string' value='/dev/SDRCFlightJoystick'/>
</node>
</group>

<!-- <group>
<remap from='joy' to='joy1'/>
<node pkg='joy' name='joy1' type='joy_node'>
<param name='dev' type='string' value='/dev/input/js1'/>
</node>
</group> -->

<!-- Axes -->
<param name="axis_linear" value="1" type="int"/>
<param name="axis_angular" value="0" type="int"/>
<param name="scale_linear" value="2" type="double"/>
<param name="scale_angular" value="2" type="double"/>
<param name='joy_pub_topic' type='string' value='/cmd_vel'/>

<!-- NOTE: pgk and type do not have to match-->
<node pkg="joystick_handler" type="joystick_handler" name="teleop" output="screen"/>
</launch>
29 changes: 29 additions & 0 deletions control/joystick_handler/joystick_handler_flight_turtle.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<launch>
<!-- Turtlesim Node-->
<!-- <node pkg="turtlesim" type="turtlesim_node" name="sim"/> -->

<!-- joy node -->
<group>
<remap from='joy' to='j0'/>
<node pkg='joy' name='j0' type='joy_node'>
<param name='dev' type='string' value='/dev/SDRCFlightJoystick'/>
</node>
</group>

<!-- <group>
<remap from='joy' to='joy1'/>
<node pkg='joy' name='joy1' type='joy_node'>
<param name='dev' type='string' value='/dev/input/js1'/>
</node>
</group> -->

<!-- Axes -->
<param name="axis_linear" value="1" type="int"/>
<param name="axis_angular" value="0" type="int"/>
<param name="scale_linear" value="2" type="double"/>
<param name="scale_angular" value="2" type="double"/>
<param name='joy_pub_topic' type='string' value='/turtle1/cmd_vel'/>

<!-- NOTE: pgk and type do not have to match-->
<node pkg="joystick_handler" type="joystick_handler" name="teleop" output="screen"/>
</launch>
53 changes: 25 additions & 28 deletions control/joystick_handler/src/joystick_handler.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <sensor_msgs/Joy.h>
#include "Configuration.h"
#include "../include/Configuration.h"
// #include "joystick/RoboteqCommand.h"

// To use: run:
Expand Down Expand Up @@ -44,7 +44,6 @@ enum joystickInputs
// float value[21];
// };


class JoystickHandler
{
public:
Expand All @@ -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_;

Expand All @@ -63,21 +62,19 @@ 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_);
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<sensor_msgs::Joy>("j"+std::to_string(joynum), 10, &JoystickHandler::joyCallback, this);
joy_sub_ = nh_.subscribe<sensor_msgs::Joy>("j" + std::to_string(joynum), 10, &JoystickHandler::joyCallback, this);

std::string topic_name;
nh_.getParam("joy_pub_topic", topic_name);
Expand All @@ -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");

Expand Down
4 changes: 0 additions & 4 deletions extras/arduino-sample/include/Configuration.h

This file was deleted.

Loading