How to control ARDUINO with joystick?
Hello everyone. I am trying to control led using joystick. My joystick connect with joy node to jetson nano, jetson nano connect to Arduino also. I am sending input from my joystick to Arduino, Arduino control led. As long as I press the joystick button I want the LED to light, when I release the button I want LED to low. my led blink when I press the button but I release the button led doesn’t off. Is anyone help me to solve this problem. I read button and axes veriable from joystick but I cant transfer this data to Arduino.
This is my arduino code
#include <stdint.h>
#include <stdlib.h>
#include <ros.h>
#include <std_msgs/Float32.h>
#include <sensor_msgs/Joy.h>
void joydata ( const sensor_msgs::Joy& joy)
{
if ((joy.buttons[1] >= 0.5) )
{
digitalWrite(2, HIGH - digitalRead(2));
}
else if (joy.buttons[1] <= 0.5)
{
digitalWrite(2, LOW - digitalRead(2));
}
else {
delay(500);
digitalWrite(2, LOW - digitalRead(2));
}
}
ros::NodeHandle nh;
ros::Subscriber<sensor_msgs::Joy> sub1("joy", joydata);
void setup()
{
pinMode(2, OUTPUT); //set up the LED
nh.initNode();
nh.subscribe(sub1);
Serial.begin(57600);
}
void loop() {
nh.spinOnce();
delay(10);
}
I take from axes and button variable
header:
seq: 9606
stamp:
secs: 1571665519
nsecs: 387521698
frame_id: ''
axes: [-0.0, -0.0, -0.0, 1.0, 1.0, -0.0, -0.0, -0.0]
buttons: [0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
header:
seq: 9607
stamp:
secs: 1571665523
nsecs: 24873820
frame_id: ''
axes: [-0.0, -0.0, -0.0, 1.0, 1.0, -0.0, -0.0, -0.0]
buttons: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
Edit: This is final verison of my code. Sometimes Arduino doesn't read joystick input when I send data. Doesn't catch the input.
I did 0.05 ms for nh.spinOnce();
This way i can prevent this error.
I want control Arduino'S Led with joystick concurrently. Sometimes Arduino's Leds stay blink. How can I do control LED simultaneously?
#include <stdint.h>
#include <stdlib.h>
#include <ros.h>
#include <std_msgs/Float32.h>
#include <sensor_msgs/Joy.h>
void joydata ( const sensor_msgs::Joy& joy)
{
int sol;
int solcapraz;
int ileri;
sol = digitalRead(2);
solcapraz = digitalRead(4);
ileri = digitalRead(6);
if (joy.buttons[4] == 1 && joy.axes[0] >= 0.5 && joy.axes[1] >= 0.5)
{
digitalWrite(2, LOW);
sol = 0;
digitalWrite(6, LOW);
ileri = 0;
digitalWrite(4, HIGH);
}
else if (joy.axes[0] <= 0.5 && solcapraz == 1 && joy.axes[1] <= 0.5) {
digitalWrite(4, LOW);
solcapraz = 0;
}
else if (joy.buttons[4] >= 0.75 && joy.axes[0] >= 0.5)
{
digitalWrite(6, LOW);
ileri = 0;
digitalWrite(4, LOW);
solcapraz = 0;
digitalWrite(2, HIGH);
}
else if (joy.axes[0] <= 0.5 && sol == 1) {
digitalWrite(2, LOW);
sol = 0;
}
else if (joy.buttons[4] == 1 && joy.axes[1] >= 0.5 )
{
digitalWrite(2, LOW);
sol = 0;
digitalWrite(4, LOW);
solcapraz = 0;
digitalWrite(6, HIGH);
}
else if (joy.axes[0] <= 0.5 && ileri == 1 && joy.axes[1] <= 0.5) {
digitalWrite(6, LOW);
ileri = 0;
}
}
ros::NodeHandle nh;
ros::Subscriber<sensor_msgs::Joy> sub1("joy", joydata);
void setup()
{
pinMode(2, OUTPUT); //set up the LED
pinMode(4, OUTPUT); //set up the LED
pinMode(6, OUTPUT); //set up the LED
nh.initNode();
nh.subscribe(sub1);
}
void loop() {
nh.spinOnce();
delay(0.05);
}
Asked by serhatzengin on 2019-10-21 09:17:48 UTC
Answers
This is my Joystick conttrolled mini car project code.
#include <digitalWriteFast.h>
#include <stdint.h>
#include <stdlib.h>
#include <ros.h>
#include <std_msgs/Float32.h>
#include <std_msgs/String.h>
#include <sensor_msgs/Joy.h>
ros::NodeHandle nh;
//std_msgs::String str_msg;
float xhizi;
float yhizi;
int hizcarpani;
const int in1 = 4; /*sag arka teker*/
const int in2 = 2;
const int in3 = 7; /*sol arka teker*/
const int in4 = 6;
const int ena1 = 9;/*pwm cıkisi sag arka teker*/
const int enb1 = 3; /*pwm cıkisi sol arka teker*/
const int in2_1 = 13; /*sag on teker*/
const int in2_2 = 12;
const int in2_3 = 8;/*sol on teker*/
const int in2_4 = 5;
const int ena2 = 11; /*pwm cıkisi sag on teker*/
const int enb2 = 10;/*pwm cıkisi sol on teker*/
void LHLH() {
digitalWriteFast(in1, LOW);/* sag arka teker geri git*/
digitalWriteFast(in2, HIGH);
digitalWriteFast(in3, LOW); /* sol arka teker geri git*/
digitalWriteFast(in4, HIGH);
digitalWriteFast(in2_1, LOW);
digitalWriteFast(in2_2, HIGH);
digitalWriteFast(in2_3, LOW);
digitalWriteFast(in2_4, HIGH);
}
void HLHL() {
digitalWriteFast(in1, HIGH);
digitalWriteFast(in2, LOW);
digitalWriteFast(in3, HIGH);
digitalWriteFast(in4, LOW);
digitalWriteFast(in2_1, HIGH);
digitalWriteFast(in2_2, LOW);
digitalWriteFast(in2_3, HIGH);
digitalWriteFast(in2_4, LOW);
}
void HLLH() {
digitalWriteFast(in1, HIGH);
digitalWriteFast(in2, LOW);
digitalWriteFast(in3, LOW);
digitalWriteFast(in4, HIGH);
digitalWriteFast(in2_1, HIGH);
digitalWriteFast(in2_2, LOW);
digitalWriteFast(in2_3, LOW);
digitalWriteFast(in2_4, HIGH);
}
void LHHL() {
digitalWriteFast(in1, LOW);
digitalWriteFast(in2, HIGH);
digitalWriteFast(in3, HIGH);
digitalWriteFast(in4, LOW);
digitalWriteFast(in2_1, LOW);
digitalWriteFast(in2_2, HIGH);
digitalWriteFast(in2_3, HIGH);
digitalWriteFast(in2_4, LOW);
}
void sagtamgaz() {
analogWrite(ena1, 92 * hizcarpani); /*sag arka teker */
analogWrite(enb1, 35 * hizcarpani); /*sol arka teker */
analogWrite(ena2, 92 * hizcarpani); /*Sag on teker */
analogWrite(enb2, 35 * hizcarpani); /*sol on teker */
}
void soltamgaz() {
analogWrite(ena1, 35 * hizcarpani); /*sag arka teker */
analogWrite(enb1, 92 * hizcarpani); /*sol arka teker */
analogWrite(ena2, 35 * hizcarpani ); /*Sag on teker */
analogWrite(enb2, 92 * hizcarpani); /*sol on teker */
}
void tamgaz() {
analogWrite(ena1, 92 * hizcarpani);
analogWrite(enb1, 92 * hizcarpani);
analogWrite(ena2, 92 * hizcarpani);
analogWrite(enb2, 92 * hizcarpani);
}
void fren() {
digitalWriteFast(in1, LOW);
digitalWriteFast(in2, LOW);
digitalWriteFast(in3, LOW);
digitalWriteFast(in4, LOW);
analogWrite(ena1, 0);
analogWrite(enb1, 0);
digitalWriteFast(in2_1, LOW);
digitalWriteFast(in2_2, LOW);
digitalWriteFast(in2_3, LOW);
digitalWriteFast(in2_4, LOW);
analogWrite(ena2, 0);
analogWrite(enb2, 0);
}
void Hareketet(float xhizi, float yhizi, int hizcarpani) {
if (xhizi >= 0.2 && yhizi <= -0.2) { /* solgeri */
LHLH();
sagtamgaz();
}
else if ( xhizi <= -0.2 && yhizi >= 0.2) { /* sagcaprazileri */
HLHL();
soltamgaz();
}
else if (xhizi >= 0.2 && yhizi <= 0.2) {/*sol*/
HLLH();
tamgaz();
}
else if ( xhizi >= 0.2 && yhizi >= 0.2) {/*solileri*/
HLHL();
sagtamgaz();
}
else if ( xhizi <= 0.2 && yhizi >= 0.2) {/*ileri git*/
HLHL();
tamgaz();
}
else if ( xhizi <= -0.2 && yhizi >= 0) { /* sag */
LHHL();
tamgaz();
}
else if (xhizi <= -0.2 && yhizi <= -0.2) { /* saggeri */
LHLH();
soltamgaz();
}
else if ( xhizi >= -0.2 && yhizi <= -0.2) { /* geri */
LHLH();
tamgaz();
}
else {
fren();
}
}
void joydata ( const sensor_msgs::Joy& joy)
{
int tetik = joy.buttons[4];
//joy.axes[0];
//joy.axes[1];
if (tetik >= 0.5 && ((joy.axes[0] <= 0.7 && joy.axes[0] >= 0.2 ) || (joy.axes[0] <= -0.2 && joy.axes[0] >= -0.7) || (joy.axes[1] <= 0.7 && joy.axes[1] >= 0.2 ) || (joy.axes[1] <= -0.2 && joy.axes[1] >= -0.7))) {
hizcarpani = 1;
Hareketet(joy.axes[0], joy.axes[1], hizcarpani);
}
else if (tetik >= 0.5 && ((joy.axes[0] <= 1 && joy.axes[0] > 0.7 ) || (joy.axes[0] < -0.7 && joy.axes[0] >= -1) || (joy.axes[1] < -0.7 && joy.axes[1] >= -1) || (joy.axes[1] <= 1 && joy.axes[1] > 0.7 ))) {
hizcarpani = 2.75;
Hareketet(joy.axes[0], joy.axes[1], hizcarpani);
}
else {
fren();
}
}
ros::Subscriber<sensor_msgs::Joy> sub1("joy", joydata);
void setup()
{
pinMode(3, OUTPUT);
pinMode(9, OUTPUT); //set up the LED
pinMode(10, OUTPUT);
pinMode(11, OUTPUT);
nh.initNode();
nh.subscribe(sub1);
TCCR1B = TCCR1B & B11111000 | B00000001;/*pwm frekansı ayarlandı 31372.55 D9 ve D10 pin*/
TCCR2B = TCCR2B & B11111000 | B00000001;/*pwm frekansı ayarlandı 31372.55 D3 ve D11 pin*/
}
void loop() {
nh.spinOnce();
Asked by serhatzengin on 2019-12-29 16:49:14 UTC
Comments
Is there any particular reason why you subtract
digitalRead(2)
in your calls todigitalWrite()
?Also I notice the final
else
is unreachable yes?Asked by Tejas Kumar shastha on 2019-10-21 10:10:06 UTC
Thanks for your attention. I Sent my problem after review. Please look another comment. I didnt write there because number of characters was not enough for comment.
Asked by serhatzengin on 2019-10-22 05:59:53 UTC