Skip to content

Commit

Permalink
joystick accelerator control finished, tested
Browse files Browse the repository at this point in the history
  • Loading branch information
NeilNie committed Jan 20, 2019
1 parent 0b29f08 commit bfa79b8
Show file tree
Hide file tree
Showing 6 changed files with 84 additions and 70 deletions.
Binary file removed .DS_Store
Binary file not shown.
101 changes: 56 additions & 45 deletions .idea/workspace.xml

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

Binary file removed arduino/.DS_Store
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,12 @@
#define LPWM 6
#define M_PI 3.14159265359
#define POT_MAX 100
#define POT_MIN 0
#define POT_MIN 30
#define LA_MIN 0
#define LA_MAX 0
#define LA_PIN 0

ros::NodeHandle nh;
ros::NodeHandle nh;

boolean joystick_enabled = false;
float target_speed = 0.0;
Expand All @@ -34,11 +34,10 @@ void cruise_callback( const std_msgs::Float32& cmd_msg) {

void joystick_callback( const std_msgs::Float32& cmd_msg) {

if (joystick_enabled) {

if (cmd_val > 0) {
if (joystick_enabled == 1) {
if (cmd_msg.data >= 0) {
cmd_val = mapf(cmd_msg.data, 0, 1, POT_MIN, POT_MAX);
} else if (cmd_val < 0) {
} else {
// engage brakes
}
}
Expand Down Expand Up @@ -77,7 +76,6 @@ void setup() {
// set the slaveSelectPin as an output:
pinMode (slave_Select_Pin, OUTPUT);
digitalWrite(slave_Select_Pin, LOW);

// initialize SPI:
SPI.begin();
}
Expand All @@ -86,18 +84,12 @@ void loop() {

potWrite(slave_Select_Pin, B00010001, cmd_val);
potWrite(slave_Select_Pin, B00010010, cmd_val);

/*
if (cruise_speed == -1) {
potWrite(slave_Select_Pin, B00010001, 0);
potWrite(slave_Select_Pin, B00010010, 0);
press_break(1);
delay(1000);
release_break(1);
Serial.println("brakes engaged");
}*/

pos_msg.data = cmd_val;
pos_pub.publish(&pos_msg);

nh.spinOnce();
delay(5);
}


Expand Down
7 changes: 6 additions & 1 deletion ros/src/gui/launch/rqt.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,15 @@
<include file="$(find cv_camera)/launch/start_camera.launch"/>

<!-- setup the Arduino serial -->
<node name="serial_node" pkg="rosserial_python" type="serial_node.py">
<node name="serial_node_1" pkg="rosserial_python" type="serial_node.py">
<param name="port" value="/dev/ttyACM0" />
</node>

<!-- setup the Arduino (braking accelerator) serial -->
<node name="serial_node_2" pkg="rosserial_python" type="serial_node.py">
<param name="port" value="/dev/ttyACM1" />
</node>

<!-- start joystick -->
<include file="$(find joy)/launch/joystick.launch"/>

Expand Down
16 changes: 11 additions & 5 deletions ros/src/sensors/joystick/scripts/selective_output.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,26 +13,32 @@ class SelectiveOutput(object):
def __init__(self):

self.output = None
self.left_stick_y = None
rospy.init_node('selective_output')

rospy.Subscriber('/sensor/joystick/joy', Joy, callback=self.joystick_input_callback, queue_size=5)
self.publisher = rospy.Publisher('/sensor/joystick/left_stick_x', data_class=Float32, queue_size=5)

rate = rospy.Rate(24)
self.publisher1 = rospy.Publisher('/sensor/joystick/left_stick_x', data_class=Float32, queue_size=5)
self.publisher2 = rospy.Publisher('/sensor/joystick/right_stick_y', data_class=Float32, queue_size=5)
rate = rospy.Rate(30)

while not rospy.is_shutdown():

if self.output is not None:
if self.output is not None and self.left_stick_y is not None:
data = Float32()
data.data = self.output
self.publisher.publish(data)
self.publisher1.publish(data)

data2 = Float32()
data2.data = self.left_stick_y
self.publisher2.publish(data2)

rate.sleep()

def joystick_input_callback(self, data):

inputs = data.axes
self.output = inputs[0]
self.left_stick_y = inputs[4]
# rospy.loginfo(self.output)


Expand Down

0 comments on commit bfa79b8

Please sign in to comment.