3. Feature: Teleoperation - FAAMT/ros_ugv_ultron GitHub Wiki

Teleoperation, also called remote control, involves controlling a machine from a distance. It enables a human operator to interact with a remote entity without being physically present. In this project, it is facilitated by the Robot Operating System (ROS), an open-source middleware framework.

We use two ROS packages: exmachina (dev) & rosserial (git). Once we launch a roscore, a collection of nodes and programs required for a ROS-based system, we can run commands to execute the nodes and programs in the package. Let's examine the packages.

Remote Keyboard Control with exmachina package

Package Name: exmachina
Install Instructions: git clone [email protected]:FAAMT/ros_ugv_ultron.git or you can manually download.
Run Command: rosrun exmachina exmachina.py
Node Information: The node was designed to read keyboard input and publish it to a topic named 'keyboard_input.' The script initializes a ROS node called 'exmachina' and sets up a publisher to the 'keyboard_input' topic, using the rospy.Publisher function from the ROS Python library.

#!/usr/bin/env python
import rospy
import sys
from std_msgs.msg import String
from sys import stdin
import getch
import time

The following functions are defined to facilitate the node's operation:

def keyboard_input_pub():
    pub = rospy.Publisher('keyboard_input', String, queue_size=1)
    rospy.init_node('exmachina', anonymous=True)
    return pub

def exmachina_init_rate():
    rate = rospy.Rate(1000) # 1hz
    return rate

The main part of the script:

if __name__ == '__main__':
    pub_0 = keyboard_input_pub()
    rate = exmachina_init_rate()

    try:
        while(1):
                msg = getch.getch()
                if(msg == "" or msg == ""):
                     break
                # print(msg)
                pub_0.publish(msg)
                rospy.loginfo(msg)
                          

    except rospy.ROSInterruptException:
        pass

The script continuously listens for keyboard input and publishes the received characters to the 'keyboard_input' topic. It runs at a rate of 1000 Hz, reading input and publishing until Ctrl+C or Ctrl+Z is pressed to terminate it. This enables remote robot control through keyboard inputs in the ROS environment.

Note: If using this package, ensure that the exmachina.py script uses the actual Ctrl+C or Ctrl+Z keys in the if statement if(msg == "" or msg == ""): to avoid an infinite loop.

Serial Communication with rosserial_python Package

Package Name: rosserial_python
Install Instructions: git clone https://github.com/ros-drivers/rosserial.git (noetic branch)
Run Command: rosrun rosserial_python serial_node.py /dev/ttyACM0 _baud:=57600 (for Arduino Mega 2560)
Node Information: The rosserial_python package facilitates serial communication between ROS and microcontrollers, enabling seamless integration of low-level microcontroller code with ROS. This integration simplifies the control and interaction of robots and devices.

For more information, usage examples, and integration guidance, please refer to the official rosserial_python repository.

Arduino Mega 2560 ROS Publisher & Subscriber

The relevant source file for this phase of the project is the arduino_ws/ultron_teleoperation.ino (C++).

After verifying the correct wiring and functionality of the Arduino Mega 2560, as demonstrated in the Wiring A Robot page, we can proceed to configure the essential Arduino ROS publishers and subscribers for teleoperation.

Library Inclusions and ROS Node Setup:
This segment includes the necessary libraries for the project, such as ROS (Robot Operating System) and standard message types. It initializes the ROS node handle.

#include <ros.h>
#include <std_msgs/String.h>
#include <Arduino.h>
#include <HardwareSerial.h>

ros::NodeHandle nh;

Subscriber Callback:
The "keyboard_input" callback function is established here. It handles incoming messages from the "keyboard_input" topic and stores the received data in the "data" variable.

std_msgs::String data;
std_msgs::String str_msg;

void keyboard_input(const std_msgs::String& key){
  Serial.println("Heard Something");
  data.data = key.data;
}
ros::Subscriber<std_msgs::String> key("keyboard_input", &keyboard_input);

Additional Movement Functions:
This section contains new functions added for motor capability, such as rotating left and rotating right.

void rotateleft(void){
  analogWrite(DC1ENA, 255);
  analogWrite(DC1ENB, 255);
  analogWrite(DC2ENA, 255);
  analogWrite(DC2ENB, 255); 

  //Wheel 1
  digitalWrite(DC1IN1, HIGH);
  digitalWrite(DC1IN2, LOW);

  //Wheel 2
  digitalWrite(DC1IN3,LOW);
  digitalWrite(DC1IN4, HIGH);

  //Wheel 3
  digitalWrite(DC2IN1, LOW);
  digitalWrite(DC2IN2, HIGH);

  //Wheel 4
  digitalWrite(DC2IN3,HIGH);
  digitalWrite(DC2IN4, LOW);
}

void rotateright(void){
  analogWrite(DC1ENA, 255);
  analogWrite(DC1ENB, 255);
  analogWrite(DC2ENA, 255);
  analogWrite(DC2ENB, 255); 

  //Wheel 1
  digitalWrite(DC1IN1, LOW);
  digitalWrite(DC1IN2, HIGH);

  //Wheel 2
  digitalWrite(DC1IN3,HIGH);
  digitalWrite(DC1IN4, LOW);

  //Wheel 3
  digitalWrite(DC2IN1, HIGH);
  digitalWrite(DC2IN2, LOW);

  //Wheel 4
  digitalWrite(DC2IN3,LOW);
  digitalWrite(DC2IN4, HIGH);
}

Setup Function:
This segment sets up the initial configurations for the ULTRON robot. It sets all the required pins to OUTPUT mode for motor control. It initializes the ROS node, subscribes to the "keyboard_input" topic, and starts serial communication.

void setup()
{
  pinMode (DC1IN1, OUTPUT);
  pinMode (DC1IN2, OUTPUT);
  pinMode (DC1IN3, OUTPUT);
  pinMode (DC1IN4, OUTPUT);
  pinMode (DC1ENA, OUTPUT);
  pinMode (DC1ENB, OUTPUT);
  pinMode (DC2IN1, OUTPUT);
  pinMode (DC2IN2, OUTPUT);
  pinMode (DC2IN3, OUTPUT);
  pinMode (DC2IN4, OUTPUT);
  pinMode (DC2ENA, OUTPUT);
  pinMode (DC2ENB, OUTPUT);

  nh.initNode();
  nh.subscribe(key);
  Serial.begin(57600);
}

Command Strings and Motion Control:
This segment defines strings that represent different commands, such as moving forward, backward, left, right, stopping, rotating left, and rotating right. In the main loop, the code reads the data received from the "keyboard_input" topic and performs the corresponding action based on the command strings. Appropriate functions are called to control ULTRON's movements, and there are delays for smooth motion control.

String move_forward  = "w";
String move_backward = "s";
String move_left     = "a";
String move_right    = "d";
String rotate_right  = "e";
String rotate_left   = "q";
String stop          = "x";
int motion_period = 50; 

void loop(){
  Serial.println("Device Active");
  const String input = data.data;
  delay(10);
  if(rotate_right.compareTo(input) == 0){
    str_msg.data = "Rotating right!";
    rotateright();
    delay(motion_period / 4);
    wait();
  }
  else if(rotate_left.compareTo(input) == 0){
    str_msg.data = "Rotating left!";
    rotateleft();
    delay(motion_period / 4);
    wait();
  }
  else if(stop.compareTo(input) == 0){
    str_msg.data = "Stopping!";
    wait();
    delay(motion_period);
  }
  else if(move_forward.compareTo(input) == 0){
    str_msg.data = "Moving forward!";
    forward();
    delay(motion_period);
    wait();
  }
  else if(move_backward.compareTo(input) == 0){
    str_msg.data = "Moving backward!";
    backward();
    delay(motion_period);
    wait();
  }
  else if(move_right.compareTo(input) == 0){
    str_msg.data = "Moving right!";
    right();
    delay(motion_period);
    wait();
  }
  else if(move_left.compareTo(input) == 0){
    str_msg.data = "Moving left!";
    left();
    delay(motion_period);
    wait();
  }
  nh.spinOnce();
}

Demo Video: Teleoperation

ultron-demo-002-teleoperation-terminal-compressed.mp4
⚠️ **GitHub.com Fallback** ⚠️