Lesson 5: Move control—ros_arduino_bridge

ros_arduino_bridge package includes Arduino libraray (ROSArduinoBridge) and a series of ROS package for control based on Arduino, using standard ROS message and service. Functions in the package are:

  • Supports ping Sonar and Sharp infrared sensors
  • Read data from universal analog and digital signal sensors
  • Control the output of digital signals
  • Supports PWM servo control
  • base controller

In the Diego 1 # robot we mainly use the base controller and PWM servo control, in order to adapt to Diego 1 # selected hardware environment, we need to make the necessary changes to the package, then we step by step to install And transform the package.

1.  ros_arduino_bridge installation

ros_arduino_bridge github:https://github.com/hbrobotics/ros_arduino_bridge

1.1. Download
Go to the src directory in your workspace directory

cd ~/catkin_ws/src
git clone https://github.com/hbrobotics/ros_arduino_bridge.git

1.2. Compile

compile in workspace

cd <catkin_ws>
catkin_make

1.3. Copy Arduino lib

In the ros_arduino_bridge directory there will be a ros_arduino_firmware subdirectory, it's src subdirectory is Arduino library files, and sample code, you can copy to the corresponding Arduino IDE library directory

$ cd SKETCHBOOK_PATH
$ cp -rp  `rospack find ros_arduino_firmware`/src/libraries/ROSArduinoBridge -T ROSArduinoBridge

ROSArduinoBridge can also be copied to other windows, Mac computer Arduino IDE environment, after the restart can be used
这里写图片描述

2.Development in Arduino

2.1.Create diego 1# Arduino project

Open the sample code for ROSArduinoBridge from Example and save it as your favorite project name. We only need to modify the sample code according to our own needs.。
这里写图片描述

2.2.exemple code introduction

  • ROSArduinoBridge.ino main code
  • commands.h Serial command is predefined
  • diff_controller.h PID
  • encoder_driver.h Encoder, where only for Arduino UNO, using the interrupt interface D2, D3, and analog interfaces A2, A3; so the output of the motor encoder wiring in accordance with this rules need to pay attention to the encoder to have two outputs
    The left side of the motor code output D2, D3; the right side of the motor code output A2, A3
  • encoder_driver.ino Encoder
  • motor_driver.h Motor-driven interface definition, with different motor drive board to achieve the definition of the three functions of this document
  • motor_driver.inoMotor driver to achieve the code, according to the predefined choice of different driver board library, where I use the L298P, so you need to implement a new driver library, will be introduced later

  • sensors.h Sensor implementation file
  • servos.hThe implementation of the steering gear

2.3.Code changes

2.3.1 ROSArduinoBridge.ino

The main changes are as follows:

Enable Base Controller

#define USE_BASE      // Enable the base controller code
//#undef USE_BASE     // Disable the base controller code
/* Define the motor controller and encoder library you are using */
#ifdef USE_BASE
   /* The Pololu VNH5019 dual motor driver shield */
   //#define POLOLU_VNH5019

   /* The L298P dual motor driver shield*/
   #define L298P


   /* The Pololu MC33926 dual motor driver shield */
   //#define POLOLU_MC33926

   /* The RoboGaia encoder shield */
   //#define ROBOGAIA

   /* Encoders directly attached to Arduino board */
   #define ARDUINO_ENC_COUNTER
#endif
/* Maximum PWM signal */
#define MAX_PWM        255//最大的PWM为255

2.3.2. motor_driver.ino

Increased support for L298P motor driver boards

/***************************************************************
Motor driver definitions

Add a "#elif defined" block to this file to include support
for a particular motor driver. Then add the appropriate
#define near the top of the main ROSArduinoBridge.ino file.

*************************************************************/
#ifdef USE_BASE

#if defined POLOLU_VNH5019
/* Include the Pololu library */
#include "DualVNH5019MotorShield.h"

/* Create the motor driver object */
DualVNH5019MotorShield drive;

/* Wrap the motor driver initialization */
void initMotorController() {
drive.init();
}

/* Wrap the drive motor set speed function */
void setMotorSpeed(int i, int spd) {
if (i == LEFT) drive.setM1Speed(spd);
else drive.setM2Speed(spd);
}

// A convenience function for setting both motor speeds
void setMotorSpeeds(int leftSpeed, int rightSpeed) {
setMotorSpeed(LEFT, leftSpeed);
setMotorSpeed(RIGHT, rightSpeed);
}
#elif defined POLOLU_MC33926
/* Include the Pololu library */
#include "DualMC33926MotorShield.h"

/* Create the motor driver object */
DualMC33926MotorShield drive;

/* Wrap the motor driver initialization */
void initMotorController() {
drive.init();
}

/* Wrap the drive motor set speed function */
void setMotorSpeed(int i, int spd) {
if (i == LEFT) drive.setM1Speed(spd);
else drive.setM2Speed(spd);
}

// A convenience function for setting both motor speeds
void setMotorSpeeds(int leftSpeed, int rightSpeed) {
setMotorSpeed(LEFT, leftSpeed);
setMotorSpeed(RIGHT, rightSpeed);
}
#elif defined L298P
#include "DualL298PMotorShield.h"

/* Create the motor driver object */
DualL298PMotorShield drive;
/* Wrap the motor driver initialization */
void initMotorController() {
drive.init();
}

/* Wrap the drive motor set speed function */
void setMotorSpeed(int i, int spd) {
if (i == LEFT) drive.setM1Speed(spd);
else drive.setM2Speed(spd);
}

// A convenience function for setting both motor speeds
void setMotorSpeeds(int leftSpeed, int rightSpeed) {
setMotorSpeed(LEFT, leftSpeed);
setMotorSpeed(RIGHT, rightSpeed);
}

#else
#error A motor driver must be selected!
#endif

#endif

2.3.3. ecoder_driver.h修改

/* *************************************************************
Encoder driver function definitions - by James Nugen
************************************************************ */

#ifdef ARDUINO_ENC_COUNTER
//below can be changed, but should be PORTD pins;
//otherwise additional changes in the code are required
#define LEFT_ENC_PIN_A PD2 //pin 2
#define LEFT_ENC_PIN_B PD3 //pin 3

//below can be changed, but should be PORTC pins
#define RIGHT_ENC_PIN_A PC2 //pin A2 
#define RIGHT_ENC_PIN_B PC3 //pin A3 
#endif
long readEncoder(int i);
void resetEncoder(int i);
void resetEncoders();

2.3.4. ecoder_driver.ino修改

/* Interrupt routine for RIGHT encoder, taking care of actual counting */
ISR (PCINT1_vect){
static uint8_t enc_last=0;

enc_last <<=2; //shift previous state two places
enc_last |= (PINC & (3 << 2)) >> 2; //read the current state into lowest 2 bits 

right_enc_pos += ENC_STATES[(enc_last & 0x0f)];
//right_enc_pos=enc_last;
}

2.3.5. L298P Driver

Put the .h and .cpp files in the same directory and copy them to the Arduino IDE library file directory.

DualL298PMotorShield.h代码

#ifndef DualL298PMotorShield_h
#define DualL298PMotorShield_h

#include <Arduino.h>

class DualL298PMotorShield
{
  public:  
    // CONSTRUCTORS
    DualL298PMotorShield(); // Default pin selection.
    DualL298PMotorShield(unsigned char M1DIR, unsigned char M1PWM,
                           unsigned char M2DIR, unsigned char M2PWM); // User-defined pin selection. 

    // PUBLIC METHODS
    void init(); // Initialize TIMER 1, set the PWM to 20kHZ. 
    void setM1Speed(int speed); // Set speed for M1.
    void setM2Speed(int speed); // Set speed for M2.
    void setSpeeds(int m1Speed, int m2Speed); // Set speed for both M1 and M2.

  private:
    static const unsigned char _M1DIR = 4;
    static const unsigned char _M2DIR = 7;
    static const unsigned char _M1PWM = 5;
    static const unsigned char _M2PWM = 6;
};

#endif

DualL298PMotorShield.cpp

#include "DualL298PMotorShield.h"

// Constructors ////////////////////////////////////////////////////////////////

DualL298PMotorShield::DualL298PMotorShield()
{
  //Pin map

}


// Public Methods //////////////////////////////////////////////////////////////
void DualL298PMotorShield::init()
{
// Define pinMode for the pins and set the frequency for timer1.

  pinMode(_M1DIR,OUTPUT);
  pinMode(_M1PWM,OUTPUT);
  pinMode(_M2DIR,OUTPUT);
  pinMode(_M2PWM,OUTPUT);

}
// Set speed for motor 1, speed is a number betwenn -400 and 400
void DualL298PMotorShield::setM1Speed(int speed)
{
  unsigned char reverse = 0;

  if (speed < 0)
  {
    speed = -speed;  // Make speed a positive quantity
    reverse = 1;  // Preserve the direction
  }
  if (speed > 255)  // Max PWM dutycycle
    speed = 255;
  if (reverse)
  {
    digitalWrite(_M1DIR,LOW);
    analogWrite(_M1PWM, speed);
  }
  else
  {
    digitalWrite(_M1DIR,HIGH);
    analogWrite(_M1PWM, speed);
  }    
}

// Set speed for motor 2, speed is a number betwenn -400 and 400
void DualL298PMotorShield::setM2Speed(int speed)
{
  unsigned char reverse = 0;

  if (speed < 0)
  {
    speed = -speed;  // Make speed a positive quantity
    reverse = 1;  // Preserve the direction
  }
  if (speed > 255)  // Max PWM dutycycle
    speed = 255;
  if (reverse)
  {
    digitalWrite(_M2DIR,LOW);
    analogWrite(_M2PWM, speed);
  }
  else
  {
    digitalWrite(_M2DIR,HIGH);
    analogWrite(_M2PWM, speed);
  }
}

// Set speed for motor 1 and 2
void DualL298PMotorShield::setSpeeds(int m1Speed, int m2Speed)
{
  setM1Speed(m1Speed);
  setM2Speed(m2Speed);
}

修改完成后变可以编译upload到Arduino UNO上了。

3.ROS pc development

3.1.Configure your robot parameters
Go to the configuration file directory

$ roscd ros_arduino_python/config

Copy a new configuration file

$ cp arduino_params.yaml my_arduino_params.yaml

Edited by nano

sudo nano my_arduino_params.yaml

Following is my_arduino_params.yaml has been modified,The main change is to enable the base Controller, modify the PID parameters, modify the robot parameters:

# For a direct USB cable connection, the port name is typically
# /dev/ttyACM# where is # is a number such as 0, 1, 2, etc
# For a wireless connection like XBee, the port is typically
# /dev/ttyUSB# where # is a number such as 0, 1, 2, etc.

port: /dev/ttyACM0
baud: 57600
timeout: 0.1

rate: 50
sensorstate_rate: 10

use_base_controller: True
base_controller_rate: 10

# For a robot that uses base_footprint, change base_frame to base_footprint
base_frame: base_link

# === Robot drivetrain parameters
wheel_diameter: 0.02900 
wheel_track: 0.18 
encoder_resolution: 2 
gear_reduction: 75.0 
motors_reversed: True

# === PID parameters
Kp: 10
Kd: 12
Ki: 0
Ko: 50
accel_limit: 1.0

# === Sensor definitions.  Examples only - edit for your robot.
#     Sensor type can be one of the follow (case sensitive!):
#     * Ping
#     * GP2D12
#     * Analog
#     * Digital
#     * PololuMotorCurrent
#     * PhidgetsVoltage
#     * PhidgetsCurrent (20 Amp, DC)



sensors: {
  #motor_current_left:   {pin: 4, type: PololuMotorCurrent, rate: 5},
  #motor_current_right:  {pin: 7, type: PololuMotorCurrent, rate: 5},
  #ir_front_center:      {pin: 2, type: GP2D12, rate: 10},
  #sonar_front_center:   {pin: 5, type: Ping, rate: 10},
  arduino_led:          {pin: 13, type: Digital, rate: 5, direction: output}
}

we can run it ,after modified.

3.2. run

start roscore

roscore

and path to bash

. ~/catkin_ws/devel/setup.bash

start node

roslaunch ros_arduino_python arduino.launch

follow is the sheetshot
这里写图片描述

At this time we can release the Twist message to control the robot's operation, such as:

rostopic pub /cmd_vel geometry_msgs/Twist -r 1 -- '[2.0, 0.0, 0.0]' '[0.0, 0.0, 1.8]'

Run this command, the robot will be rotated in situ, with the following order to view odom information, this information will continue to change


rostopic echo /odom
这里写图片描述

At this point the robot has been able to control according to the Twist message, released for the move base to use the odom information due to the chassis used by the two-wheel drive tracked chassis, which is typical of the differential control chassis, but due to the motor characteristics, the robot's load, And other issues, will lead to the actual speed of the two motors and expectations do not match, there can not go straight line situation, the next course we will continue to modify the ros_arduino_bridge function package to achieve the two motor dual PID speed control mechanism.

Lesson 4: Move control—differential control Kinematic model

Differential control of the chassis movement, completely dependent on the control of the two drive wheels, the basic control method is as follows:

  • Forward:Both driving wheel moving forward simultaneously
  • Backward: Both driving wheel moving backward simultaneously
  • Left turn: Left driving wheel speed is less than right driving wheel speed
  • Right turn: Left driving wheel speed is greater than right driving wheel speed

In the actual installation, the general two drive motor just symmetrical installation, this time generally one of the motor control line of the positive and negative reverse installation, in order to achieve the above control effect,The specific connection method can be foundLesson 2: Hardware diagram。Only by understanding the corresponding kinematic model we can do precisely control, let’s start by discussing the kinematic model of the differential chassis

 

1.Kinematics model

1.1 Right-handed Coordinate System

The movement of the robot must be carried out in a certain coordinate system, and ROS uses the right-hand coordinate system, so we need to first understand the right-hand coordinate system

Right hand coordinates as shown above, the right hand fist, thumb pointing to the Z axis, the index finger pointing to the X axis, the middle finger pointing to the Y axis, corresponding to our plane movement of the robot, motion control is to control its coordinates in the world XY Axis axis of the movement, Z-axis direction can be seen as still, that is, during the movement of the Z-axis direction of the line speed is always 0, from the robot coordinate system to see the Y-axis line speed is 0, but the angular velocity In other words, the angular velocity in the Z-axis direction is not zero, and the angular velocity in the XY-axis direction is zero;

1.2 Single drive wheel motion analysis

For a crawler-type chassis, if you simply look at the movement of a drive wheel, its Y-axis in the world coordinate system is also static, only the X-axis movement, that is, the Y-axis direction of the speed is 0

1.3 Analysis of Differential Chassis Motion of Double Drive Wheel

Because of the difference in the speed of the two drives, the entire chassis is turned toward the slow side, and based on this principle, we can control the speed of the two drive motors to control the steering of the entire robot. If we want to control the robot to go straight, That is, must be the speed of the two drive wheels is the same, otherwise it will turn. As shown in the figure below, when the speed of the left and right wheels YZ is 0, the right drive wheel speed is greater than the left drive wheel speed, turning from the top of the robot to the left.

Based on this principle in the robot control time, we will have two problems to be solved

  • Given the robot line speed and angular velocity, how to break down the control parameters of the two drive wheels
  • How to calculate the speed and angular velocity of the robot according to the speed value of the two driving wheels, and then calculate the mileage data,

 

2.Decompose the speed to the control parameters of the two drive wheels

The speed of the robot refers to the speed between two adjacent control times. Since the ROS itself is dependent on the high frequency of the transmission control command to accurately control the robot, we commonly used the control frequency is> 10hz, so fast Frequency, we can assume that the robot in such a short period of time through the arc between the two positions to replace the straight line. Based on the above assumptions, we can introduce the robot coordinate system.

Assume that the moving speed of the robot coordinate system is V and the time interval is Δt. Then the distance traveled in the robot coordinate system v * Δt,

Assuming that the trajectories of the two drive wheels are l, then the distance from the left wheel is v * Δt-l * sin (θ), and the linear velocity of the left wheel is deduced. Vl = (v * Δt – l * sin Θ)) / Δt; and the linear velocity of the right wheel is Vr = (v * Δt + l * sin (θ)) / Δt

3.Track deduction

3.1 Push the track according to speed

 

Assume that the velocity of the robot coordinate system is V and the time interval is Δt. Then the distance traveled in the robot coordinate system v * Δt, then the decomposition of the world coordinate system within the x-axis and y-axis travel distance is

Δx=v*Δt*cos(θ)

Δy=v*Δt*sin(θ)

The curvature of the rotation is:

Δθ=w*Δt

Then a period of time odom:

x=x+v*Δt*cos(θ)

y=y+v*Δt*sin(θ)

θ=θ+Δθ

The above is based on the speed of the robot in the ideal state according to the line speed and angular velocity to deduce the track, but the reality is that the robot does not necessarily follow the set speed of control, and there will be errors, this time we are more use of sensors Data to push the track, such as laser radar, depth camera, motor code plate, ultrasonic, gyroscope and other sensor data, some robots use only one of them, advanced robots are using a variety of sensor data fusion algorithm to improve the voyage deduction The accuracy of the. Here we introduce the most commonly used based on the motor code data track deduction.

3.2 According to the code data to carry out the track

The code wheel gives the distance between the two drive motors in the time period of Δt, and the angle of rotation can be calculated as follows::

sin(Δθ)=((Δxr-Δxl)/2)/l

Since Δt is very short, the distance traveled is very short, so do the following approximation

Δθ=sin(Δθ)=((Δxr-Δxl)/2)/l

The distance traveled by the entire machine is the average of the two motor travel distances (Δxl + Δxr) / 2

Then the XY axis is mapped to the world coordinate system:

Δx=cos(θ)*(Δxl+Δxr)/2

Δy=sin(θ)*(Δxl+Δxr)/2

Then a period of time odom:

x=x+cos(θ)*(Δxl+Δxr)/2

y=y+sin(θ)*(Δxl+Δxr)/2

θ=θ+Δθ

Understanding the motion model, we can follow the principle of the model to control the movement of the robot.

Lesson 3: Software architecture & environment deployment

1.Sofware architecture

Diego 1# features are based on ROS platform and many open-source software, software architecture is as shown in following figure.

 

  • OS is based on Ubuntu mate 16.04 and ROS release is kinetic
  • ros_arduino_bridge:The communication package between ROS and Arduino

    ros_arduino_firmware:Running on Arduino, responsible for control of corresponding module in Raspberry, like PID calculator, sensor control, servo control

    ros_arduino_node:Running on Raspberry as a node of ROS, providing related node service and topic

    base_controller:Running on Raspberry, subscripting Twist message, implementing control command translation based on the configuration of robot, also releasing odom message for other module

  • SLAM

    Gmapping:Construction indoor map based on laser radar data or pointcloud data, also requiring odom data

    Hector:Construction indoor map based on laser radar data or pointcloud data without odom data

    amcl:Positioning based on existing map based on laser radar data or pointcloud data

    move_base:Path planning, sending Twist message to control robot moving to specified location 

  • Vision

    Openni:Depth camera driver package using to drive xtion and Kinect to produce point cloud data 

    usb_cam: usb camera drive package

  • Voice & Speech

    sphinx:offline voice recognition and synthesis package, mainly focus on English

    Xunfei voice: Online voice recognition and synthesis system

  • moveit:Mechanical manipulator control package to control mechanical manipulator moving to specified position and obstacle avoiding
  • teleop_twist_keyboard-master:Controlling robot via keyboard

2.Building Ubuntu SD

Raspberry is based armhf architecture, according to ROS website, ROS kinetic+Ubuntu Xenial is required to support armhf.

and the recommended xenial release is Ubuntu MATE 16.04.2 LTS

So here we use the recommended release to avoid uncertain problems.

For ROS installation information, please refer to http://wiki.ros.org/ROS/Installation

2.1. Ubuntu MATE 16.04.2 LTS Download

Download address:https://ubuntu-mate.org/download/

Here Raspberry Pi release is recommended, after download and unzip you will get the mirror file.

2.2. Building Ubuntu SD on Mac

a.  Open a terminal

b. Using cd command to the mirror file located folder, here mirror file is at desktop

cd Desktop

c. Check the file name of sd card

diskutil list

d. Unmount disk

diskutil unmountDisk /dev/disk3

e. Executing write flash command

sudo dd bs=1m if=ubuntu-mate-16.04.2-desktop-armhf-raspberry-pi.img of=/dev/disk3

Here is the procedure:

For windows OS, Win32DiskImager software with graphic interface can be used for write flash, we will not go detail here.

After above steps, SD card is ready to plug in Raspberry. For the first boot, necessary configuration is required, more detail please refer to :https://ubuntu-mate.org/raspberry-pi/

3. ROS installation

This part follows ROS installation guidance:http://wiki.ros.org/kinetic/Installation/Ubuntu

3.1 Setting sources.list

sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'

 3.2 Setting key

sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116

3.3 System update

sudo apt-get update

3.4 ROS kinetic desktop installation

ROS kinetic desktop release is selected considering of calculation capability of Raspberry, required package will be loaded according to requirements.

sudo apt-get install ros-kinetic-desktop

3.5 rosdep    Initial rosdep

sudo rosdep init
rosdep update

3.6 Preference setting 

echo "source /opt/ros/kinetic/setup.bash" >> ~/.bashrc
source ~/.bashrc

Until now, ROS has been installed on Raspberry and ready for work.

4.ROS working space creation

 To begin ROS development, first task is to create ROS working space

$ mkdir -p ~/catkin_ws/src
$ cd ~/catkin_ws/src
$ catkin_init_workspace

Lesson 2: Hardware diagram

1. The connection of Raspberry

As the master controller of Diego 1#, Raspberry connects with other modules via following interface to implement its control logic.

  • One USB2.0 interface connects with USB Type B interface of Arduino UNO. Raspberry sends commands to Arduino UNO via serial port. This interface also provides power supply to Arduino UNO.
  • One USB2.0 interface connects with USB Micro of Flash lidar F4 laser radar. Laser radar sends data via serial port.
  • Buck module provides power supply to Raspberry via USB interface.

Following chart shows the connection of Raspberry:

2. The connection of Arduino UNO

As the executive controller of Diego 1#, UNO connects with related hardware directly 

  • Connecting with Raspberry via USB Type B interface to receive control command from serial bus.
  • Connecting with servo control board via IIC interface, also sending servo control command.
  • Connecting with motor shield L298P via PWM interface to control motor speed.
  • Conneting with motor shield L298P via digital output pin to control motor direction.
  • Connecting with hall-sensor signal output pin via out-INT and hardware interrupt pin to get motor rotation turns
  • 5V voltage output provides power supply of servo control board and hall-sensor of motor.

Following chart show the connection of Arduino.

L298P is a shield of Aruduio, it can be plug-in Arduino directly, for convenient cable trace, an IO extension board of Arduino is used for L298P, as shown in following figure.

3. The connection of servo control board and 6 DOF manipulator

16-line servo control board PCA9685

  • Each servo current is around 0.5A, total 3.5A current is required for 6 DOF manipulator plus servo of mechanical grabber, so servo control board needs a separate powered supply.
  • In servo control board, 0~5th channel are used for manipulator control and 6th channel is used for mechanical grabber control.

4. Power supply

  • As there are many electrical equipment and high requirement on current in Diego 1#, so dual power supply solution is provided, one for Raspberry, Arduino and chassis motor and the other for servo of mechanical grabber.

5. Other

  • Mechnical part of Diego 1# uses finished product solution , so the assembly can refer to related product manual.
  • During installation, different types of screw driver and electric drill will be used
  • Power supply must take care of the power requirement of equipment,  otherwise uncertain question will occur.

Lesson 1: Hardware BOM

Diego 1# has 2 version, normal one and plus one. In normal version, Raspberry 3 works as master controller while mini PC with higher configuration and capability is used in plus version. Due to the limitation of Raspberry 3 calculation capability, depth camera and related features are not included in normal version, while in plus version, full features are included.

Diego 1# specification:
Length:27cm 
Width:27cm
Height:41cm
Weight:4kg

Following table listed Diego#1 related hardware components, including hardware appearance, name, quantity and features.

PhotoNameCountFeaturediego 1#中的作用
RaspBerry PI31•Broadcom BCM2837 芯片组,运行频率 1.2 GHz
•64 位四核 ARM Cortex-A53
•802.11 b/g/n 无线局域网
•蓝牙 4.1(经典和低能耗)
•双核 Videocore IV® 多媒体协处理器
•1 GB LPDDR2 存储器
•支持所有最新的 ARM GNU/Linux 分发和 Windows 10 IoT
•MicroUSB 连接器,用于 2.5 A 电源
•1 x 10/100 以太网端口
•1 x HDMI 视频/音频连接器
•1 x RCA 视频/音频连接器
•4 个 USB 2.0 端口
•40 个 GPIO 引脚
•芯片天线
•DSI 显示连接器
•microSD 卡插槽
•尺寸:85 x 56 x 17 mm
•主控制板
•Ubuntu mate 16.04
•ROS kinetic
•Other ROS package
Arduino UNO1•处理器 ATmega328
•工作电压 5V
•输入电压(推荐) 7-12V
•输入电压(范围) 6-20V
•数字IO脚 14 (其中6路作为PWM输出)
•模拟输入脚 6
IO脚直流电流 40 mA
•3.3V脚直流电流 50 mA
•Flash Memory 32 KB (ATmega328,其中0.5 KB 用于 bootloader)
•SRAM 2 KB (ATmega328)
•EEPROM 1 KB (ATmega328)
•工作时钟 16 MHz
•控制底盘两路驱动电机PWM信号输出
•采集底盘两路电机的里程数据
•通过IIC与舵机控制板连接控制6自由度舵机
•运行ROSArduinoBridge-diego
Arduino L298P two line motor control board1•电机驱动电压:外部输入3-35V 内部输入:6-12V
•逻辑端消电流:<30MA
•驱动电流:2A
•驱动峰值电流:4A
•最大功率:25W
•工作温度:-25℃-130℃
•PWMA:D5(~)引脚
•DIRA:D4引脚
•PWMB:D6(~)引脚
•DIRB:D7引脚
•控制底盘两路驱动电机
•为底盘两路驱动电机提供外接9v两路直流电源
Arduino IO shield1单独引出了Arduino的如下接口:
•全部数字与模拟接口
•IIC接口
•舵机控制器接口
•蓝牙模块通信接口
•SD卡模块通信接口
•APC220无线射频模块通信接口
•超声波传感器接口
•12864液晶串行与并行接口
•连接底盘马达的霍尔传感器电源线
•连接底盘马达的霍尔传感器信号线
•通过IIC接口与16路舵机控制板连接
16 line Servo control board1•I2C通信
•内置16路PWM驱动器
•支持级联最多62块舵机驱动板相连
•控制6自由度机械臂的6个MG996R舵机
•控制机械爪的一个MG996R舵机
Buck1•大功率5A输出,低纹波
•板载USB输出
•恒压恒流两种可调模式
•过流保护
•板载电压、电流、功率显示
•为树莓派提供5v USB供电
Buck1•大功率10A输出,低纹波
•为舵机提供5V电源
Micro SDHC 32G1•速度:80 M/S
•速度等级:Class 10
•树莓派OS存储
9V 18650 battery1•标称电压 :9V
•放电电流 :3.0A
•充电电流 :0.5A
•内阻 :≤60mΩ
•最高充电电压 :9.0V
•为底盘电机马达供电
•为树莓派供电
•为Arduino供电
12V 18650 battery1•标称电压 :12V
•放电电流 :6.0A
•充电电流 :0.5A
•内阻 :≤60mΩ
•最高充电电压 :12.6V
•最低放电电压 :9.0V
•为6自由度机械臂舵机供电
•为机械爪舵机供电
T300 chassis1•材料:铝合金
•表面:已氧化处理
•颜色:银色
•履带:金属(银色)
•大小:270*270*110mm (长*宽*高)
•重量:1.6kg
•工作载重:约7KG
•机器人底盘
EAI Flash lidar F41•360度全方位扫描,10赫兹自适应扫描频率,每秒4500次激光测距
•不低于8米的测距范围,测量量程1%的解析度
•噪音低,寿命长
•Class 1 激光安全标准
•为机器人提供2D平面360度的测量数据,作为SLAM绘制地图,导航的基础数据
6 - DOF manipulator1•机架材质选用加厚硬质合金数控加工而成
•全手臂采用MG996R金属齿轮舵机
•所有运动关节采用优质轴承链接。
•机臂后加有主控板固定底座,随机械臂运动。
•设计的体积和精度,适合于教学与试验。
•手臂底座采用优质全钢大轴承固定。
•产品标配带夹具固定盘
•作为机器人的手臂
Talon1•材质:硬质铝合金
•重量:约40g(不含舵机)
•最大张角间距:86mm
•整体长:83mm(闭合时的整体最长长度)
•整体宽1:150mm(张开时的最大整体宽度)
•整体宽2:55mm(闭合时的最大整体宽度)
•整体厚:54mm(带舵机爪子的最大整体厚度)
•作为机器人的手
servo line3•线材类型:黑红白并线
•插头分为:标准型插头
•长度分为:30cm
•舵机线规格:22AWG 60芯
•由于机械臂和机械手的原配舵机线不够长,需要延长线
holder2•材料:2mm铝板
•表面处理:喷砂氧化
•尺寸:58*37*25.5mm
•重量:16克
•固定组合支架
holder2•材料:2mm铝板
•表面处理:喷砂氧化
•尺寸:37*55*20mm
•重量:12克
•固定组合支架
holder4•材料:2mm铝板
•表面处理:喷砂氧化
•尺寸:90*55*44mm
•重量:50克
•固定组合支架
Acrylic3•颜色:黑色
•厚度:4mm
•固定机械臂
•固定Arduino UNO
•固定树莓派 3
USB2.0 line TypeA~USB micro B1•USB Type A micro B接口•给树莓派供电
USB2.0 line Type A~Type B1•USB Type B 接口•连接树莓派与Arduino
DC Pins2•DC母插头
•线长20cm
•电池与降压模块连接
Power linen•导体结构:17/0.12TS 镀锡铜丝•连接降压模块与舵机控制模块
•连接9V电池与电机控制模块
Dupont linen•母头-母头
•母头-公头
•连接Arduino 扩展板与舵机控制版
Copper Postn•m3
•m2.5
•固定零件
•树莓派使用m2.5
Screwn•m3
•m2.5
•固定零件
•树莓派使用m2.5
Nutsn•m3
•m2.5
•固定零件
•树莓派使用m2.5

During hardware installation,  related tools like screwdriver, plier, electric drill will be used but not listed. 

Posts navigation

1 2 3 4
Scroll to top