Code Monkey home page Code Monkey logo

curio_firmware's Introduction

Firmware for Curio

An Arduino Mega 2560 rosserial_arduino client for controlling a Sawppy rover. To be used in conjunction with the curio packages.

Overview

The firmware implements an instance of a rosserial_client that runs on the Arduino and is managed by a rosserial node running on the rover's onboard computer.

The firmware provides:

  • A base controller to control the rover's servos
  • A decoder for a radio control receiver

Both functions can be enabled or disabled by compile time switches, and the radio control decoder can be configured to process either pulse width modulated signals or a radio control serial communication protocol called SUMD.

Dependencies

  • rosserial_python - manages the host-side of the serial connection and communication to other ROS nodes.
  • rosserial_arduino - provides the client Arduino ROS interface: publish and subscribe messages, access parameters, etc.
  • curio_msgs - define the message format used for controlling servos and publishing radio control PWM data.
  • EnableInterrupt - used by the PWM decoder to handle interrupts for each of the RC channels.

Installation

Here we describe how to build and install the firmware to your Arduino. In the following SKETCHBOOK_PATH is the path to your Arduino sketchbook directory.

Clone the repository into your catkin workspace, then build:

cd ~/curio_ws/src
git clone https://github.com/srmainwaring/curio_firmware.git
cd ~/curio_ws
catkin build

Build and install the ROS libraries for the Arduino:

cd ~/curio_ws
rosrun rosserial_arduino make_libraries.py .
cp -rp ./ros_lib SKETCHBOOK_PATH/libraries

Add a file ros_dummy.h to the ROS Arduino library in SKETCHBOOK_PATH/libraries/ros_lib/ containing the following:

// ros_dummy.h
// A placeholder so that the Arduino IDE can find header files
// in subdirectories of ros_lib when re-declaring ros.h 
// in your project
//
// In your copy of ros.h include this file. 
//
// Resources:
//  http://wiki.ros.org/rosserial_arduino/Tutorials/NodeHandle%20and%20ArduinoHardware
//  https://www.codeproject.com/Articles/1279552/Rodney-A-Long-Time-Coming-Autonomous-Robot-Part-7

#ifndef _ROS_LIB_ROS_DUMMY_H_
#define _ROS_LIB_ROS_DUMMY_H_

namespace ros {
}

#endif // _ROS_LIB_ROS_DUMMY_H_

(My thanks to Phil Hopley's excellent blog for his explanation of why this is is needed).

Copy the firmware source to the sketchbook folder:

cp -rp `rospack find curio_firmware`/firmware/curio_firmware SKETCHBOOK_PATH/curio_firmware

From the Arduino IDE open the sketch and adjust configuration settings described in the section below as required. Finally compile the sketch and download it to your Arduino.

Configuration

The main sketch file curio_firmware.ion contains the following configuration flags:

ENABLE_ARDUINO_LX16A_DRIVER

  • 1: Enable the Arduino LX-16A driver. The Arduino will subscribe to servo commands and publish unfiltered servo positions.
  • 0: Disable the Arduino LX-16A driver. All servo control is carried out by the Python base controller.

Note that the corresponding flag in curio_base/src/base_controller.py must also be set.

ENABLE_RADIO_CONTROL_DECODER

  • 1: Enable the radio control decoder. The Arduino will publish radio control PWM values on a curio_msgs/Channels message.
  • 0: Disable the radio control decoder.

ENABLE_RADIO_CONTROL_SUMD

  • 1: Use the SUMD decoder.
  • 0: Use the PWM decoder.

Hardware

The following wiring instructions apply to the Arduino Mega 2560.

Lewansoul BusLinker

  • 5V on the BusLinker to Arduino +5V
  • GND on the BusLinker to Arduino GND
  • TX on the BusLinker to Arduino RX1 PIN 19
  • RX on the BusLinker to Arduino TX1 PIN 18

Radio control receiver

SUMD

  • + on the receiver to Arduino +5V
  • - on the receiver to Arduino GND
  • S channel 5 on the receiver to Arduino RX2 PIN 17

PWM

  • + on the receiver to Arduino +5V
  • - on the receiver to Arduino GND
  • S channel 1 on the receiver to Arduino PIN 2
  • S channel 2 on the receiver to Arduino PIN 3
  • S channel 3 on the receiver to Arduino PIN 4
  • S channel 4 on the receiver to Arduino PIN 5
  • S channel 5 on the receiver to Arduino PIN 6
  • S channel 6 on the receiver to Arduino PIN 7

Usage

See the documentation for curio.

ROS

The parameters, publications and subscriptions supported are affected by the configuration settings. For instance if radio control is disabled the curio_msgs::Channels messages will not be published.

Parameters

  • ~wheel_servo_ids : list
    A list of integer wheel servo ids, has (default [11, 12, 13, 21, 22, 23])
  • ~steer_servo_ids : list
    A list of integer steering servo ids, has (default [111, 131, 211, 231])
  • ~steer_servo_angle_offsets : list
    A list of integer steering servo angle offsets for adjusting steering trim, has (default [0, 0, 0, 0]

Publications

  • servo/positions : curio_msgs/CurioServoPositions
    The wheel and steering servo positions (rate 30Hz)
  • servo/states : curio_msgs/CurioServoStates
    The diagnostic state of each servo (rate 1Hz)
  • radio/channels : curio_msgs/Channels
    PWM values for one or more radio control channels

Subscriptions

  • servo/commands : curio_msgs/CurioServoCommands
    The commanded duty and position for the wheel and steering servos

License

This software is licensed under the BSD-3-Clause license found in the LICENSE file in the root directory of this source tree.

curio_firmware's People

Contributors

srmainwaring avatar

Stargazers

 avatar

Watchers

 avatar  avatar  avatar

curio_firmware's Issues

What do the parameters of this array represent

What do the parameters of this array buf[] represent?

void LobotSerialServoAngleAdjust(HardwareSerial &SerialX, uint8_t id, uint8_t deviation)
{
byte buf[7];
buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER;
buf[2] = id;
buf[3] = 4;
buf[4] = LOBOT_SERVO_ANGLE_OFFSET_ADJUST;
buf[5] = deviation;
buf[6] = LobotCheckSum(buf);
SerialX.write(buf, 7);
}

1

1

Firmware code is different

Why is the firmware I built different from yours?

This is my firmware code
lobot_serial.cpp:

#include "lobot_serial.h"
/*

  • Serial message frame - total size is length + 3 bytes
  • header 2 bytes 0x55, 0x55
  • id 1 byte 0 - 253
  • length 1 byte
  • command 1 byte
  • data length - 3
  • checksum 1 byte
    */

// Macro function get lower 8 bits of A
#define GET_LOW_BYTE(A) (uint8_t)((A))

// Macro function get higher 8 bits of A
#define GET_HIGH_BYTE(A) (uint8_t)((A) >> 8)

// Macro Function put A as higher 8 bits B as lower 8 bits which amalgamated into 16 bits integer
#define BYTE_TO_HW(A, B) ((((uint16_t)(A)) << 8) | (uint8_t)(B))

#define LOBOT_SERVO_FRAME_HEADER 0x55
#define LOBOT_SERVO_MOVE_TIME_WRITE 1
#define LOBOT_SERVO_MOVE_TIME_READ 2
#define LOBOT_SERVO_MOVE_TIME_WAIT_WRITE 7
#define LOBOT_SERVO_MOVE_TIME_WAIT_READ 8
#define LOBOT_SERVO_MOVE_START 11
#define LOBOT_SERVO_MOVE_STOP 12
#define LOBOT_SERVO_ID_WRITE 13
#define LOBOT_SERVO_ID_READ 14
#define LOBOT_SERVO_ANGLE_OFFSET_ADJUST 17
#define LOBOT_SERVO_ANGLE_OFFSET_WRITE 18
#define LOBOT_SERVO_ANGLE_OFFSET_READ 19
#define LOBOT_SERVO_ANGLE_LIMIT_WRITE 20
#define LOBOT_SERVO_ANGLE_LIMIT_READ 21
#define LOBOT_SERVO_VIN_LIMIT_WRITE 22
#define LOBOT_SERVO_VIN_LIMIT_READ 23
#define LOBOT_SERVO_TEMP_MAX_LIMIT_WRITE 24
#define LOBOT_SERVO_TEMP_MAX_LIMIT_READ 25
#define LOBOT_SERVO_TEMP_READ 26
#define LOBOT_SERVO_VIN_READ 27
#define LOBOT_SERVO_POS_READ 28
#define LOBOT_SERVO_OR_MOTOR_MODE_WRITE 29
#define LOBOT_SERVO_OR_MOTOR_MODE_READ 30
#define LOBOT_SERVO_LOAD_OR_UNLOAD_WRITE 31
#define LOBOT_SERVO_LOAD_OR_UNLOAD_READ 32
#define LOBOT_SERVO_LED_CTRL_WRITE 33
#define LOBOT_SERVO_LED_CTRL_READ 34
#define LOBOT_SERVO_LED_ERROR_WRITE 35
#define LOBOT_SERVO_LED_ERROR_READ 36

//#define LOBOT_DEBUG 1 /Debug :print debug value/

byte LobotCheckSum(byte buf[])
{
byte i;
uint16_t temp = 0;
for (i = 2; i < buf[3] + 2; i++) {
temp += buf[i];
}
temp = ~temp;
i = (byte)temp;
return i;
}

void LobotSerialServoMove(HardwareSerial &SerialX, uint8_t id, int16_t position, uint16_t time)
{
byte buf[10];
if(position < 0)
position = 0;
if(position > 1000)
position = 1000;
buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER;
buf[2] = id;
buf[3] = 7;
buf[4] = LOBOT_SERVO_MOVE_TIME_WRITE;
buf[5] = GET_LOW_BYTE(position);
buf[6] = GET_HIGH_BYTE(position);
buf[7] = GET_LOW_BYTE(time);
buf[8] = GET_HIGH_BYTE(time);
buf[9] = LobotCheckSum(buf);
SerialX.write(buf, 10);
}

void LobotSerialServoStopMove(HardwareSerial &SerialX, uint8_t id)
{
byte buf[6];
buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER;
buf[2] = id;
buf[3] = 3;
buf[4] = LOBOT_SERVO_MOVE_STOP;
buf[5] = LobotCheckSum(buf);
SerialX.write(buf, 6);
}

void LobotSerialServoAngleAdjust(HardwareSerial &SerialX, uint8_t id, uint8_t deviation)
{
byte buf[7];
buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER;
buf[2] = id;
buf[3] = 4;
buf[4] = LOBOT_SERVO_ANGLE_OFFSET_ADJUST;
buf[5] = deviation;
buf[6] = LobotCheckSum(buf);
SerialX.write(buf, 7);
}

void LobotSerialServoAngleWrite(HardwareSerial &SerialX, uint8_t id)
{
byte buf[6];
buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER;
buf[2] = id;
buf[3] = 3;
buf[4] = LOBOT_SERVO_ANGLE_OFFSET_WRITE;
buf[5] = LobotCheckSum(buf);
SerialX.write(buf, 6);
}

void LobotSerialServoSetID(HardwareSerial &SerialX, uint8_t oldID, uint8_t newID)
{
byte buf[7];
buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER;
buf[2] = oldID;
buf[3] = 4;
buf[4] = LOBOT_SERVO_ID_WRITE;
buf[5] = newID;
buf[6] = LobotCheckSum(buf);
SerialX.write(buf, 7);

#ifdef LOBOT_DEBUG
Serial.println("LOBOT SERVO ID WRITE");
int debug_value_i = 0;
for (debug_value_i = 0; debug_value_i < buf[3] + 3; debug_value_i++)
{
Serial.print(buf[debug_value_i], HEX);
Serial.print(":");
}
Serial.println(" ");
#endif

}

void LobotSerialServoSetMode(HardwareSerial &SerialX, uint8_t id, uint8_t Mode, int16_t Speed)
{
byte buf[10];

buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER;
buf[2] = id;
buf[3] = 7;
buf[4] = LOBOT_SERVO_OR_MOTOR_MODE_WRITE;
buf[5] = Mode;
buf[6] = 0;
buf[7] = GET_LOW_BYTE((uint16_t)Speed);
buf[8] = GET_HIGH_BYTE((uint16_t)Speed);
buf[9] = LobotCheckSum(buf);

#ifdef LOBOT_DEBUG
Serial.println("LOBOT SERVO Set Mode");
int debug_value_i = 0;
for (debug_value_i = 0; debug_value_i < buf[3] + 3; debug_value_i++)
{
Serial.print(buf[debug_value_i], HEX);
Serial.print(":");
}
Serial.println(" ");
#endif

SerialX.write(buf, 10);
}

void LobotSerialServoLoad(HardwareSerial &SerialX, uint8_t id)
{
byte buf[7];
buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER;
buf[2] = id;
buf[3] = 4;
buf[4] = LOBOT_SERVO_LOAD_OR_UNLOAD_WRITE;
buf[5] = 1;
buf[6] = LobotCheckSum(buf);

SerialX.write(buf, 7);

#ifdef LOBOT_DEBUG
Serial.println("LOBOT SERVO LOAD WRITE");
int debug_value_i = 0;
for (debug_value_i = 0; debug_value_i < buf[3] + 3; debug_value_i++)
{
Serial.print(buf[debug_value_i], HEX);
Serial.print(":");
}
Serial.println(" ");
#endif

}

void LobotSerialServoUnload(HardwareSerial &SerialX, uint8_t id)
{
byte buf[7];
buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER;
buf[2] = id;
buf[3] = 4;
buf[4] = LOBOT_SERVO_LOAD_OR_UNLOAD_WRITE;
buf[5] = 0;
buf[6] = LobotCheckSum(buf);

SerialX.write(buf, 7);

#ifdef LOBOT_DEBUG
Serial.println("LOBOT SERVO LOAD WRITE");
int debug_value_i = 0;
for (debug_value_i = 0; debug_value_i < buf[3] + 3; debug_value_i++)
{
Serial.print(buf[debug_value_i], HEX);
Serial.print(":");
}
Serial.println(" ");
#endif
}

int LobotSerialServoReceiveHandle(HardwareSerial &SerialX, byte *ret)
{
bool frameStarted = false;
byte frameCount = 0;
byte dataCount = 0;
byte dataLength = 2;
byte rxBuf;
byte recvBuf[32];

while (SerialX.available()) {
rxBuf = SerialX.read();
delayMicroseconds(100);
if (!frameStarted) {
if (rxBuf == LOBOT_SERVO_FRAME_HEADER) {
frameCount++;
if (frameCount == 2) {
frameCount = 0;
frameStarted = true;
dataCount = 1;
}
}
else {
frameStarted = false;
dataCount = 0;
frameCount = 0;
}
}
if (frameStarted) {
recvBuf[dataCount] = (uint8_t)rxBuf;
if (dataCount == 3) {
dataLength = recvBuf[dataCount];
if (dataLength < 3 || dataCount > 7) {
dataLength = 2;
frameStarted = false;
}
}
dataCount++;
if (dataCount == dataLength + 3) {

#ifdef LOBOT_DEBUG
Serial.print("RECEIVE DATA:");
for (int i = 0; i < dataCount; i++) {
Serial.print(recvBuf[i], HEX);
Serial.print(":");
}
Serial.println(" ");
#endif

    if (LobotCheckSum(recvBuf) == recvBuf[dataCount - 1]) {

#ifdef LOBOT_DEBUG
Serial.println("Check SUM OK!!");
Serial.println("");
#endif

      frameStarted = false;
      memcpy(ret, recvBuf + 4, dataLength);
      return 1;
    }
    return -1;
  }
}

}
return -1;
}

int LobotSerialServoReadPosition(HardwareSerial &SerialX, uint8_t id)
{
int count = 10000;
int ret;
byte buf[6];

buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER;
buf[2] = id;
buf[3] = 3;
buf[4] = LOBOT_SERVO_POS_READ;
buf[5] = LobotCheckSum(buf);

#ifdef LOBOT_DEBUG
Serial.println("LOBOT SERVO Pos READ");
int debug_value_i = 0;
for (debug_value_i = 0; debug_value_i < buf[3] + 3; debug_value_i++)
{
Serial.print(buf[debug_value_i], HEX);
Serial.print(":");
}
Serial.println(" ");
#endif

while (SerialX.available())
SerialX.read();

SerialX.write(buf, 6);

while (!SerialX.available()) {
count -= 1;
if (count < 0)
return -1;
}

if (LobotSerialServoReceiveHandle(SerialX, buf) > 0)
ret = BYTE_TO_HW(buf[2], buf[1]);
else
ret = -1;

#ifdef LOBOT_DEBUG
Serial.println(ret);
#endif
return ret;
}

int LobotSerialServoReadVin(HardwareSerial &SerialX, uint8_t id)
{
int count = 10000;
int ret;
byte buf[6];

buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER;
buf[2] = id;
buf[3] = 3;
buf[4] = LOBOT_SERVO_VIN_READ;
buf[5] = LobotCheckSum(buf);

#ifdef LOBOT_DEBUG
Serial.println("LOBOT SERVO VIN READ");
int debug_value_i = 0;
for (debug_value_i = 0; debug_value_i < buf[3] + 3; debug_value_i++)
{
Serial.print(buf[debug_value_i], HEX);
Serial.print(":");
}
Serial.println(" ");
#endif

while (SerialX.available())
SerialX.read();

SerialX.write(buf, 6);

while (!SerialX.available()) {
count -= 1;
if (count < 0)
return -2048;
}

if (LobotSerialServoReceiveHandle(SerialX, buf) > 0)
ret = (int16_t)BYTE_TO_HW(buf[2], buf[1]);
else
ret = -2048;

#ifdef LOBOT_DEBUG
Serial.println(ret);
#endif
return ret;
}

ros_dummy.h No such file or directory

When downloading firmware through Arduino, the following error occurs:

ros.h:4:10: fatal error : ros_dummy.h No such file or directory
#include "ros_dummy.h"
compilation terminated.
exit status 1
ros_dummy.h No such file or directory

How to solve the above errors?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.