Category: CM-5 & CM-510 C programming

CM-510 firmware for using as multiple sensor item updated

CM-510 firmware and post updated

 

 

(I) Reading sensors connected to Robotis CM-510

This entry is part 5 of 5 in the series Bioloid C++ tutorial

cm-510 sensorsUsing the Dynamixel SDK instead of RoboPlus Tasks is not possible to query sensors connected to the CM-5xx controller. But, of course, using standard programming languages, like C++, and tools, line QT Creator or Eclipse, with its full featured IDEs and debuggers is a hugue gain.

So I created a firmware for the CM-510 which can be queried and receive commands to itself, including its sensors, or to Dynamyxel devices.

The idea is very simple:

This program running in the CM-510 receives:

– commands or queries to IDs of Dynamixel devices. These are not processed, only redirected to the Dynamixel bus only if it was received by serial port ( serial cable or zigbee). If it was received from the Dynamixel bus nothing is done.

– commands or queries to the CM-510 ID (I chose ID=200), like beep, or to the sensors connected to it. This commands and queries are processed in the CM-510, basically querying the sensors.

In both cases the answer is sent to the connection from which the query or command was received.

After power on the CM-510, you can select the mode with the 4 cursor keys as showed in a terminal connected to its serial port:

“For ‘Toss mode’ press (Up), for ‘Device mode’ (Down), for ‘Device debug mode’ (Left),to start press (Right)”

In the Device mode:

all the receptions and sends are through the Dynamixel bus, the CM-510 is simply another device.

In the Toss mode:

– what is received from the serial connection is sent to the Dynamixel bus or processed in the CM-510 (If sent to its ID)

-what is received from the Dynamixel bus is sent to the serial connection

Finally, the Debug mode:

is like the Device mode, but all the debug messages included in the CM-510 are sent to the serial connection.

A complete sequence with code snippets from the CM-510 program and from the code running in the other computer:

Some C++ code snippets from this example: (C# in the next post)

enum AX12Address  //and functions implemented in the CM-510 program, like
{
	ReadCM510SensorRaw = 1,
        Beep = 8,
	ReadCM510SensorFiltered = 4,
	SetSensorValuesToFilter = 5,
...
}
void doBeep()
{
    cout << "Beep" << endl;
    mySystem.dynamixelCommunication.sendOrder(100, AXS1_Buzzer, (byte) DO, (short) 500);
    usleep (200000);
    mySystem.dynamixelCommunication.sendOrder(200,MyCommunications::Beep short)5);
}

Querying sensor:

void doQuerySensor()
{
    int sensorPort=getSensorPort();
    int value=mySystem.dynamixelCommunication.readSensorValue (200,ReadCM510SensorRaw, sensorPort);
   cout << "the sensor reads: [" << value << "] " << endl << endl << endl;
}

These command and query are processed in the CM-510:

Getting the sensor value:


int executeCM510Function()
{
...
		case F_GET_SENSOR_VALUE_RAW:
			values[1] = getSensorValueRaw(parameters[1]);
			break;

		case F_GET_SENSOR_VALUE_FILTERED:
			values[1] = getSensorValueFiltered(parameters[1], sensorValuesToFilterDefined);
			break;

		case F_GET_TWO_DMS_SENSOR_VALUES:
			parametersReceived=3;
			getTwoDMSSensorsValues();
			break;

		case F_GET_MULTIPLE_SENSOR_VALUE:
			getMultipleSensorsValues();
			break;

		case F_DO_SENSOR_SCAN: 
			values[1]= sensorScan(parameters[1]);
			break;

		case F_SET_VALUE_DMS1 : //set default value DMS1
			DMS1=parameters[1];
			break;

		case F_SET_VALUE_DMS2 : //set default value DMS1
			DMS2=parameters[1];
			break;

		case F_BEEP:
			if (debugMode)
				printf("executeCM510Function beep\n");
			beep();
			break;

		case F_SET_SENSOR_VALUES_TO_FILTER:
			sensorValuesToFilterDefined=parameters[1];
			break;
	}

	return function;
}

}
...
int getSensorValueRaw(unsigned char portId)
{
ADCSRA = (1 << ADEN) | (1 << ADPS2) | (1 << ADPS1);

		setPort(portId);
		//PORTA &= ~0x80;
		//PORTA &= ~0x20;

		//_delay_us(12);				// Short Delay for rising sensor signal
		_delay_us(24);
		ADCSRA |= (1 << ADIF);		// AD-Conversion Interrupt Flag Clear
		ADCSRA |= (1 << ADSC);		// AD-Conversion Start

		while( !(ADCSRA & (1 << ADIF)) );	// Wait until AD-Conversion complete

		PORTA = 0xFC;				// IR-LED Off

		//printf( "%d\r\n", ADC); // Print Value on USART

		//_delay_ms(50);
		_delay_ms(ReadSensorDelayMS);

		return ADC;
}

 


void beep()
{
   buzzOn(100);
   buzzOff();
}

But we can do a little more with the CM-510 processor, we can do some filtering to the sensor values.

The readings from the DMS are usually somewhat erratic, so we can simply:

– discard the minimum and maximum values:

– if we take 5 more than measures, then return the average if the are more than 3, if 3 or less it

Previously we should set how many readings should be done, if not, the default number of readings are 5:

int getSensorValueFiltered(unsigned char portId, int times)
{
...
	switch(function)
	{		
		case F_GET_SENSOR_VALUE_RAW:
			values[1] = getSensorValueRaw(parameters[1]);
			break;

		case F_GET_SENSOR_VALUE_FILTERED:
			values[1] = getSensorValueFiltered(parameters[1], sensorValuesToFilterDefined);
			break;

		case F_GET_TWO_DMS_SENSOR_VALUES:
			parametersReceived=3;
			getTwoDMSSensorsValues();
			break;

		case F_GET_MULTIPLE_SENSOR_VALUE:
			getMultipleSensorsValues();
			break;

		case F_DO_SENSOR_SCAN: 
			values[1]= sensorScan(parameters[1]);
			break;

		case F_SET_VALUE_DMS1 : //set default value DMS1
			DMS1=parameters[1];
			break;

		case F_SET_VALUE_DMS2 : //set default value DMS1
			DMS2=parameters[1];
			break;

		case F_BEEP:
			if (debugMode)
				printf("executeCM510Function beep\n");
			beep();
			break;

		case F_SET_SENSOR_VALUES_TO_FILTER:
			sensorValuesToFilterDefined=parameters[1];
			break;
	}
...

We also can take values from multiple sensors with one query, but It will be explained in the next post…

Programming CM-510 with C: reading values from terminal and moving a Dynamixel AX-12

This entry is part 4 of 4 in the series Programming CM-5/CM-510

Programming CM-510 with C: reading values from terminal and moving a Dynamixel AX-12

In this post we are going to ask the ID AX-12+ that we want to move and the goal position.

The explanations are in the code as comments, I hope that there are enough comments to understand it, let me know if you can’t understand it.

The main loop is that easy:

int main(void)
{
init();

while(true) // we'll repeat this looop forever
{
int id=getId(); // get the ID of the AX-12 that we want to move
int position=getPosition(); // get the goal position
dxl_write_word( id, P_GOAL_POSITION_L, position); // sent the command to the Dynamixel
}

return 0;
}

A brief explanation of printf: printf function is much more powerful than it seems at a first sight, it admits many parameters that allow us to display a large amount of data types and formats. In In the following example %i means that in that position the message will include an integer that will be passed as a parameter after the string “AX12 ID:”. The control character “n” means a line break.

Each character in the string is stored in a memory location [A][X][1][2][ ][I][D] strings are a special case of array.

getID and getPosition are also very easy, isn’t?

/*
The next functions asks for the ID of the AX-12 to move, checking that the ID is a value between 1 and 18
*/

int getId()
{
/*
We define an array enough large, 256 bytes (characters). Probably it's enough with 4 bytes, but if we type more than the defined size we will get an error*/
char buffer[256];

/*
And we define another integer variable, it's very advisable to asign a value in the definition, in this case we assign the minimun value, 1*/
int ax12Id=1;

// puts is very similar to printf, it shows the string that it receives as parameter
puts ("nnMoving a Dynamixel");

do
{ // starting the loop
puts ("Enter the ID of the AX-12 that you wwant to move, between 1 y 18, ");
ax12Id=readInteger(buffer); // this function will read from what we type in the keyboard
//// exclamation (!) is the NOT logical operator. It will repeat the loop while the value is not valid
}while(!isValid(ax12Id, 1, 18));

// Showing the typed value
printf("AX12 ID: %in", ax12Id);

return ax12Id;
}

// Now we will repeat almost the same code that above, it should be pretty easy to write a reusable function, isn't?

int getPosition()
{
char buffer[256];
int position=0;

do
{
puts ("Enter a value between 0 and 1023 as the goal position");
position=readInteger(buffer);
}while(!isValid(position, 0, 1023));

printf("nPosition: %in", position);

return position;

The functions used to read the text from the Terminal are quite interesting, showing the use of a string. It also shows how to use the .h file (declaration) and the .c (definitions, the content of the functions):

// Body (content) of the functions that read data

/*
Recibimos una variable que tiene reservado espacio en memoria para almacenar
la cadena introducida
*/

void readString(char bufferParameter[])
{
int i=0; // We'll use this variable as index of the buffer where we will store data
do
{
bufferParameter[i]=getchar(); // it store the read character in the i position of bufferParameter
putchar(bufferParameter[i]); // showing it
if (bufferParameter[i]=='b') // if Backspace was pressed
i--; // it goes to the previous position, rewritting the previoulsy typed character
else //
i++; // it will write in the next position
}while(bufferParameter[i-1]!='n'); // while the last values is not INTRO. The symmbol ! represents the logical operator NOT

bufferParameter[i]=0; // A NULL (0, zero) is necessary in the last position of any string
}

/*
It read an string, it's converted to integer and returned
*/
int readInteger(char bufferParameter[])
{
readString(bufferParameter);
return atoi(bufferParameter);
}

You can download the sourcecode here

The language C, also C++, has some very interesting features such as the inclusion of code depending on certain conditions. This lets you use the same code for different processors by simply changing one or more parameters.

As an example, this ZIP contains a project for Dev-CPP with a version of the source files for the PC and the CM-510; simply commenting or uncommenting a line in the file “myCM510.h” (for AVR Studio you should create the appropriate project and include the sources files).

Instead of moving AX-12 it displays the text “dxl_write_word” with the parameters received. We can practice C and perform different tests on the PC without connecting any servo.

Bioloid CM-510 programming tutorial: First steps with C

This entry is part 3 of 4 in the series Programming CM-5/CM-510

Bioloid programming workshop: First steps with C

(En español)

This brief post starts the Bioloid programming workshop, using ​C, C + + and C# languages  and different controllers: ATMega (CM-510), PC, SBC.

The first steps in C programming

C language is a simple, powerful and extremely versatile tool used to develop software for industries as diverse as the automobile , medical equipment or for the software industry itself, from Microsoft Office to operating systems like Windows or Linux.

This will be a very practical programming workshop with Robotis Dynamixel servos, so I will include links tutorials anb books that include broader and deeper explanations, like C introduction (pdf). But there are a lot:

C Language Tutorial (html)
How C Programming Works (html)
Several C programming tutorials (html)

One of the simplest programs in C:

// This line that begins with two slashes is a comment

/*
These others, starting with a slash and an asterisk
are a comment too, ending with another asterisk and a slash.

The comments are very useful for explaining what we do and,
especially, why we do so, because after a few months we will not remember the details.
*/

/*
The includes are useful to announce the compiler that we will use
existing functions from other files, such as stdio.h, in this example,  to get
the printf function to display information on screen.
(This is not exactly true, but more on that later)
*/
#include

/*
This is one way to start a C program,
Creating the main function as the starting point of every C program:
*/
void main ()

// The body or content of the function starts with the following curly bracket
{

// Guess what does the following function?
printf ("Hello, World");

// And, predictably, the function ends with the closing curly bracket
}

Now we will write the first program for the CM-510

But previously you should install the software needed to program the CM-510. If you install WinAVR in “C:tools WinAVR-20100110” you can download a zip with everything ready to use.

After loading our program in the CM-510, to use RoboPlus Tasks, Motion RoboPlus Robotis and other programs, we will have to restore Robotis firmware.

# Include stdio.h
# Include "myCM510.h"

executeMovement1 void (int ax12Id)
{
dxl_write_word (ax12Id, P_GOAL_POSITION_L, 512);
}

executeMovement2 void (int ax12Id)
{
dxl_write_word (ax12Id, P_GOAL_POSITION_L, 600);
}

int main (void)
{
ax12Id int = 6;

init ();

printf ("\r \n A simple example");

printf ("\r \n Perform movement 1 with the AX-12% i", ax12Id);
executeMovement1 (ax12Id);

printf ("\r \n Pause half a second");
_delay_ms (500); // half-second pause

printf ("\r \n Beep!");
buzzOn (100); // beep

printf ("\r \n Pause for a second");
_delay_ms (1000); // pause for 1 second

printf ("\r \n Perform movement 2 with the AX-12% i", ax12Id);
executeMovement2 (ax12Id);

printf ("\r \n End");
}

The characters “\r \n” are used to jump to the next line in Windows.

If you have installed the necessary software (WinAVR must be installed in “C:tools WinAVR-20100110”) and unzip this zip file in the root directory (C: ) you have to be ready to modify, compile, or simply load the executable “hello_world.hex” in the CM-510. You will see something similar to:

01_Hello_World_CM-510

01_Hello_World_CM-510

Some explanations
dxl_write_word (ax12Id, P_GOAL_POSITION_L, 600);

This function is included in the Robotis CM-510 libraries allowing us to send commands to a Dynamixel actuator very easily. We only have to indicate the ID of the AX-12 to move (ax12Id), the code of the order that the AX-12 should execute, in this case go to the goal position (P_GOAL_POSITION_L), and the position in which has to be placed between 0 and 1024 (600 in the example).

dx_series_goal

Highlights:

Decompose the program into different parts

  •     Having previously created the init () function in myCM510.h/myCM510.c allows us to include it easily in this program.
  •     In addition to simplifying programming we can reuse the same code in different programs. This saves us from having to repeat the same code many times and, especially, have to correct faults or improve in only one point, . Later we will see how to organize directories and even how to create libraries.
  •     It also allows us to encapsulate the details, so that when the program starts growing we can handle them easily without being overwhelmed.

Showing what is doing running the program

Using the printf function we can send text to the screen that lets us know what is doing the program (printf sends to the serial port, “RoboPlus Terminal” read it  and displays it on the screen. We will lear how to read from the serial port when we start programming Bioloid using a PC or SBC)

Can you think of an easy way to avoid having two similar functions such as “void executeMovement1 (int ax12Id)” and “void executeMovement2 (int ax12Id)”?

Learning scurves with AX-12

This entry is part 2 of 3 in the series Programming Robotis Bioloid hardware

I’m learning how to use scurves with AX-12, so I’ve created a test CM-510 C program where I try different approachs. Any help will be very well received, because my goal is to control several AX-12 and I’m far far away from it!

Here is the program with an spreadsheet with the calculations (LibreOffice and Excel). I have started from an old post from Bullit in the Tribotix forum (now in PDF format at Robosavvy)

Clockwise is the standard motion, counter clockwise is the scurve intended motion

CM-5: Creating a simple “Hello World” C program

This entry is part 2 of 4 in the series Programming CM-5/CM-510

This post try to explain how to compile, load in the CM-5 (transmit) and execute a C program (a servo version of the “Hello World” classic example).

What do you need?

(You can find here how to start programming CM-5 / CM-510)

Obviously, some Bioloid hardware:

– The CM-5

– The battery or power source

– The serial cable

– An AX-12

– A cable to connect the AX-12 with the ID 17 to the CM-5. You can change the ID in the program.

What should you do?

1. Download and install the software:

1.- Download and install the Robotis RoboPlus software.

2.- Download and install WinAVR

3.- Download a Hello World example for WinAVR.

The C “Hello World” servo program is based in the original Robotis example.

4.- You should create a folder for your CM-5 program, for example c:myprojectscm5helloworld Copy there the previously downloaded helloworld.zip and unzip it.

2. Compile and link the program

1. Execute WinAVR and open the unzipped project:

( Bioloid User’s Guide.pdf could help you using WinAVR)

You should change the ID 17 of the servo for the ID of the servo you are using

2.- Compile and link. Make all:

3.- You should see “Errors: none”

4.- Transmit and execute the helloworld.hex to the CM-5

( Here you can find more info )

Well, if you only want to test the executable, you can download only the hex.

When loaded you should see an screen with two equal values as a correct “Checksum” check (in this example the value is 81, it’s calculated from the source code). If the values are not equal there is an error in the transmission.

CM5HexLoaded

5.- Every time you press the red MODE button the servo should spin

CM-510 as a multiple sensor dynamixel item (updated 21/03/2014)

This entry is part 3 of 3 in the series Programming Robotis Bioloid hardware

[UPDTATE 21/03/2014] TossModeJCA v6.5. More information and examples at (I) Reading sensors connected to Robotis CM-510. Here you have the source files.

New functions added:

#define F_GET_BATTERY_MILLIVOLTS 6
Get the current battery voltage

#define F_SET_BATTERY_LOW_LEVEL_THRESHOLD 20
Set low battery warning (two red led will be on, PLAY and AUX)

#define F_SET_BATTERY_VERY_LOW_LEVEL_THRESHOLD 21
Set VERY low battery warning, all leds on

Apart from toss commands to Dynamixel devices, All the functions CM-510 could perform are:

#define F_NO_FUNCTION  0
No function, only to initialize values

#define F_GET_SENSOR_VALUE_RAW  1
Read sensor value

#define F_GET_TWO_DMS_SENSOR_VALUES 2
[Experimental] Read 2 sensor values in one query and one answer

#define F_GET_MULTIPLE_SENSOR_VALUE 3
[Experimental] Read several sensor values in one query and one answer

#define F_GET_SENSOR_VALUE_FILTERED  4
Read sensor value, avoiding maximum and minimum values

#define F_SET_SENSOR_VALUES_TO_FILTER 5
Number of readings that will be filtered

#define F_GET_BATTERY_MILLIVOLTS 6
Get the current battery voltage

#define F_SET_BATTERY_LOW_LEVEL_THRESHOLD 20
Set low battery warning (two red led will be on, PLAY and AUX)

#define F_SET_BATTERY_VERY_LOW_LEVEL_THRESHOLD 21
Set VERY low battery warning, all leds on

#define F_BEEP 8
If there is a buzzewr it beep, if no buffer it blinks

#define F_DO_SENSOR_SCAN 9
[Experimental!!!] Using servo ID 13 runds from 300 to 700 reading and return servo por where max value read

#define F_SET_VALUE_DMS1Port 11
Set the port for the first sensor

#define F_SET_VALUE_DMS2Port 12
Set the port for the second sensor

[UPDATE 7/11/13: CM_510 TossModeJCA updated to v5.8. Several parameters error fix and somewhat faster]

My main Bioloid project is to build a robot that will have some interesting (non easily predictable but reasonable) behaviours. AntOne 3.6 is the last version:

AntOne 3.6 is based on a PDA that has the software for the behaviour and a CM-510 (ATMega 2561) that control the hardware (servos and sensors). But I discovered that standard CM-510 firmware has no command to get sensor values, so I programmed another with that function. But then I thought that it would be interesting to embed some perception functions in the CM-510.

This is a general diagrama:

Single controller

Single controller

Updated 23/2/2013

The new hex file v4.3 (the old CM-510 firmware)

Now it supports new functions, as:

– Toss Mode (up) now can read from Dynamixel and write to serial and, as the previous version, read from serial and write to Dynamixel, it allows to….
– receive from zigbee and send the data to the Dynamixel bus
– read raw sensor values
– averaged sensor values when F_SET_SENSOR_VALUES_TO_FILTER is set < 5, not including the min and the max when >= 5
– CM-510 beep
– sensor scan (still in development)

#define F_NO_FUNCTION 0
#define F_GET_SENSOR_VALUE_RAW 1
#define F_GET_TWO_DMS_SENSOR_VALUES 2
#define F_GET_MULTIPLE_SENSOR_VALUE 3
#define F_GET_SENSOR_VALUE_FILTERED 4
#define F_SET_SENSOR_VALUES_TO_FILTER 5

#define F_BEEP 8
#define F_DO_SENSOR_SCAN 9
#define F_SET_VALUE_DMS1 11
#define F_SET_VALUE_DMS2 12

C# example os use:

       private void B_ReadPort_Click(object sender, EventArgs e)
        {
            byte function = (byte)NUD_Function.Value;
            byte portId = (byte)NUD_Port.Value;

            if (portId &amp;lt; 0 || portId &amp;gt; 6)
                portId = 1;

            string strPortId=portId.ToString();

            if (function == 1 || function == 4)
            {
                short portValue = cm510.getSensorValue(function, portId);
                string str = portValue.ToString();

                TB_PortValue.Text = str;
            }
            else
            {
                if (function == 2)
                {
                    byte[] parameters = new byte[3];
                    parameters[0] = function;
                    parameters[1] = Convert.ToByte(TB_DMS1_ID.Text);
                    parameters[2] = Convert.ToByte(TB_DMS2_ID.Text);

                    short[] values = new short[3];
                    cm510.getMultipleSensorValue(parameters, values);
                    //cm510.getTwoSensorValue(function, Convert.ToByte(TB_DMS1_ID.Text), Convert.ToByte(TB_DMS2_ID.Text), values);

                    if (values.Length &amp;gt;= 2)
                    {
                        TB_DMS1_PortValue.Text = values[1].ToString();
                        TB_DMS2_PortValue.Text = values[2].ToString();
                    }
                }
                else
                {
                    if (function == 3)
                    {
                        byte[] parameters = new byte[3];
                        parameters[0] = function;
                        parameters[1] = Convert.ToByte(TB_DMS1_ID.Text);
                        parameters[2] = Convert.ToByte(TB_DMS2_ID.Text);

                        short[] values = new short[3];
                        cm510.getMultipleSensorValue(parameters, values);

                        if (values.Length &amp;gt;= 2)
                        {
                            TB_DMS1_PortValue.Text = values[1].ToString();
                            TB_DMS2_PortValue.Text = values[2].ToString();
                        }
                    }
                    else
                    {
                        if (function == 11)
                        {
                            TB_DMS1_ID.Text = strPortId;
                        }
                        else
                        {
                            if (function == 12)
                            {
                                TB_DMS2_ID.Text = strPortId;
                            }
                        }
                    }
                }
            }
        }

%d bloggers like this: