Only released in EOL distros:  

Package Summary

Simple velocity controlled arm. Teleoperation software and firmware.

  • Maintainer status: maintained
  • Maintainer: Daniel Snider <danielsnider12 AT gmail DOT com>
  • Author: Daniel Snider <danielsnider12 AT gmail DOT com>, Matthew Mirvish <matthewmirvish AT hotmail DOT com>
  • License: Unlicense
  • Source: git https://github.com/danielsnider/simple_arm.git (branch: master)

Overview

A simple arm system. Features include:

  • velocity control of arm joint motors
  • fast and slow motor speed modifier buttons
  • open and close a gripper (single speed)
  • control of a camera servo (up and down only)
  • simple Arduino firmware to talk to PWM motors and a servo

This package does not do the following:

R3 Arm

This diagram is also available in Visio format.

Package created by Ryerson University students for the University Rover Competition, summer 2017.

Quick Start

1. Install:

$ sudo apt-get install ros-kinetic-simple-arm

2. Launch:

$ roslaunch simple_arm simple_arm.launch joystick_serial_dev:=/dev/input/js0 microcontroller_serial_dev:=/dev/ttyACM0

3. Install the arm_firmware onto a microcontroller connected to the arm joint motors by PWM. The microcontroller must also be connected to the computer running the simple_arm ROS node by a serial connection (ex. USB).

4. Move your robot arm.

Nodes

simple_arm

This node converts sensor_msgs/Joy messages from the joy node into a variety of commands that are sent over serial to a microcontroller to drive the robot arm.

The button mapping was tested on a Logitech Extreme 3D Pro joystick and should only need small modifications for similar controllers.

Subscribed Topics

joy_arm (sensor_msgs/Joy)
  • Joystick state is received on this topic. See joy node for more info.

Parameters

~microcontroller_serial_device (string, default: /dev/ttyACM0)
  • The microcontroller, often an Arduino, as seen in linux, that this node will send motor commands to.
~baudrate (int, default: 9600)
  • The serial device data transmission rate in bits per second (baud).

Serial Protocol

This node communicates with the arm_firmware using a simple serial protocol. Each serial motion command is a list of floats, one for each joint.

Serial data packet:

(FLOAT) GRIP,
(FLOAT) WRIST_ROLL,
(FLOAT) WRIST_PITCH,
(FLOAT) UPPER_ELBOW,
(FLOAT) LOWER_ELBOW,
(FLOAT) BASE_YAW,
(FLOAT) CAMERA

arm_firmware

The arm_firmware microcontroller code does the minimum amount of work possible to receive motor commands from a USB serial connection and output voltages to digital PWM output to be received by motor controllers.

We connected an Arduino by USB serial to our main robot computer. We tested on a Arduino Mega 2560, however many other boards should work with the same code and setup steps thanks to PlatformIO. You may need to change to change the pin numbers.

/!\ Caution! This software does not stop moving the robot if no messages are received for certain period of time. A pull request for this is very welcome.

PlatformIO

We deploy the arm_firmware to an Arduino microcontroller using PlatformIO.

{i} We like PlatformIO: "Single source code. Multiple platforms." PlatformIO supports approximately 200Embedded Boards and all majorDevelopment Platforms. Learn more onplatformio.org.

Install and configure arm_firmware

This steps were tested on Ubuntu 16.04.

1. Install PlatformIO

$ sudo python -c "$(curl -fsSL https://raw.githubusercontent.com/platformio/platformio/master/scripts/get-platformio.py)"

# Enable Access to Serial Ports (USB/UART)
$ sudo usermod -a -G dialout <your username here>
$ curl https://raw.githubusercontent.com/platformio/platformio/develop/scripts/99-platformio-udev.rules  > /etc/udev/rules.d/99-platformio-udev.rules
# After this file is installed, physically unplug and reconnect your board.
$ sudo service udev restart

More PlatformIO install info: http://docs.platformio.org/en/latest/installation.html#super-quick-mac-linux

2. Create a PlatformIO project

$ roscd simple_arm
$ cd ./arm_firmware/
# Find the microcontroller that you have in the list of PlatformIO boards
$ pio boards | grep -i mega2560
# Use the name of your board to initialize your project
$ pio init --board megaatmega2560

More PlatformIO info: http://docs.platformio.org/en/latest/quickstart.html

3. Modify wiring if necessary

$ vim src/main.cpp +9

Depending on how you want to wire your microcontroller this wiring can be changed:

   1 struct JOINTPINS{
   2   int wrist_roll = 9; // wrist roll pin
   3   int wrist_pitch = 10; // wrist pitch pin
   4   int upper_elbow = 11; // upper elbow pin
   5   int lower_elbow = 12;  // lower elbow pin
   6   int base_yaw = 13;  // base yaw pin
   7   int grip_enable = A4;  // gripper enable pin
   8   int grip_open = A5;  // gripper open pin
   9   int grip_close = A6;  // gripper close pin
  10   int cam_tilt = 7; // camera servo pin
  11 }pins;

4. Modify PWM Settings

$ vim src/main.cpp +4

Edit the following section to match your motor controller PWM specs:

   1 // PWM specs of the Victor SP motor controller.
   2 //      https://www.vexrobotics.com/217-9090.html
   3 #define sparkMax 650 // Full-reverse input pulse
   4 #define sparkMin 2350 // Full-forward input pulse
   5 

5. Deploy Code to Arduino

$ pio run --target upload

6. Move your robot arm! B-)

Have fun!

Feedback

Feature requests, bug reports, and contributions are welcome at https://github.com/danielsnider/simple_arm.

Special thanks to anyone who sends a picture of this package in action on their robot!

Wiki: simple_arm (last edited 2017-08-20 23:13:28 by Daniel Snider)