Chassis Control Tutorial

From Waveshare Wiki
Jump to: navigation, search

Fuction Packet Introduction

UGV02 controls the robot's movement by sending a JSON message {"T":13,"X":0.25,"Z":0.3} to the serial port through Raspberry Pi. (Where T=13 represents the command for linear and angular velocity control, and X and Z represent the linear velocity in m/s and angular velocity in rad/s for controlling the robot's movement.)
In ROS, robot movement is typically controlled by publishing Twist messages through the /cmd_vel node. The Twist message type is as follows:
Twist Message.png

Twist messages cannot be directly used for chassis control. Therefore, the next step is to write a ROS2 package to subscribe to the Twist messages published by the /cmd_vel node. The obtained linear and angular velocities will be used to construct a JSON message, which will then be sent to the chassis through the serial port. This process is designed to achieve the goal of controlling the chassis.

Demo

Create Function Packet

Enter working space:

cd */ugv02/src


Create function packet

ros2 pkg create communication_module --build-type ament_python --dependencies rclpy

Chassis Control Nodes=

Create ugv02_control.py file in /ugv02/src/communication_module/communication_module/ directory:
Compile the demo code in ugv02_control.py file:

#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Twist
import serial  
import json  

# Open the sereial port   
ser = serial.Serial('/dev/ttyAMA0', 115200, timeout=1)  

class CmdVelSubscribe(Node):
    def __init__(self,name):
        super().__init__(name)
        # Create the subscriber  
        self.command_subscribe_ = self.create_subscription(Twist,"cmd_vel",self.command_callback,10)
        
    def command_callback(self,msg):
        print("msg.linear.x:  ", msg.linear.x)  
        print("msg.angular.z:  ", msg.angular.z)  
        angular_velocity = msg.angular.z
        # Prevents rotating in place at speeds too low to rotate
        if msg.linear.x == 0:
            if 0<angular_velocity<0.2:
                angular_velocity = 0.2
            elif -0.2<angular_velocity<0:
                angular_velocity = -0.2

        # Create JSON messages 
        data = {'T': '13', 'X': msg.linear.x, 'Z': angular_velocity}  

        json_data = json.dumps(data).encode('utf-8')  
        
        # Send the JSON messge to the serial port  
        ser.write(json_data) 

def main(args=None):
    rclpy.init(args=args) # Initialize rclpy
    node = CmdVelSubscribe("robot_control")  # Create a node
    rclpy.spin(node) # Keep the nodes running and test whether receive the command to exit (Ctrl+C)
    rclpy.shutdown() # turn off rclpy
    # Turn off the serial port 
    ser.close()


Modify the entry_points content in the setup.py of /ugv02/src/communication_module/ directory:

entry_points={
    console_scripts': [
        "ugv02_control = communication_module.ugv02_control:main"
    ],
},

Compile

Return the working space and compile:

cd ~/ugv02
colcon build

Run to Test

Enter the working space:

cd ~/ugv02
source ./install/setup.bash


Add permissions to the Raspberry Pi serial port (you need to run it once every time the Raspberry Pi reboots for the serial port to be called).

sudo chmod 777 /dev/ttyAMA0


Initiate the chassis control nodes:

ros2 run communication_module ugv02_control


Turn the keyboard control:

ros2 run teleop_twist_keyboard teleop_twist_keyboard


If the above sentence reports an error that the function pack cannot be found, you can install the function pack first and then run it again.
Keyboard Control Pack Installation:

sudo apt-get install ros-humble-teleop-twist-keyboard


Next, you'll be able to use the keyboard to control the robot's movements.
Keyboard controls for each key are described:



  U   I     O   
J K L
M < >

K: stop
I, J, <, L Front, Left, Back, Right
q/z: 10% increase/decrease in max speed.
w/x: 10% increase in linear speed only.
e/c: 10% increase in angular speed only.