top of page

Forum Posts

Gero
Mar 31, 2021
In Software
Hi there, in the recent years there has been a lot of progress concerning deep reinforcement learning and many publications are available that prove that machine learning can create stable gaits for robots. Mainly interesting and relatively understandable papers are for example https://arxiv.org/abs/1804.10332, where the authors created a walking and also a galloping gait based on training in simulation and a later application on the robot. In a later publication they further advanced and made it possible to learn new gaits via reinforcement directly on the robot without simulation in less than 2 hours https://arxiv.org/abs/1812.11103 There are a lot more examples and different approaches to this. Nevertheless, this is very remarkable and this made me thinking, whether we can get there also with Nybble and Bittle. But let's slow down a little. What's reinforcement learning in particular? When you look at the graph below you can get a basic understanding how this works: The Agent, in our case Nybble/Bittle is set in an Environment (e.g. flat floor). There it performs Actions like moving the limbs somehow and trying to get a Reward from the Programmer. The Reward is only given when the State is what we actually want, e.g. moving forward. Trapped in this loop our robot will try to maximize the Reward in every iteration becoming better and better in the movement. Source: https://en.wikipedia.org/wiki/Reinforcement_learning#/media/File:Reinforcement_learning_diagram.svg So what I tried to do now, is to use a simulation environment with a flat ground together with a simulation model of Nybble and wanted to make it move forward. I implemented this in the gym training environment in PyBullet with the reinforcement library Stable-Baselines3 https://stable-baselines3.readthedocs.io/en/master/index.html# . There are a lot of functional learning algorithms one can use for reinforcement learning. So for training in my case I tried an algorithm called SAC (Soft Actor-Critic) that seems to be the current state-of-the-art algorithm for reinforcement learning and applied it on Nybble to see how it performs. And the results is definitely still more a crawling than a walking gait, but it shows the potential. This is a result of reinforcement training only without any intervention from my side: The next steps are to improve training and the resulting gaits. And once the gaits are good in simulation there are two ways. One is trying to get the learning policy running on Nybble/Bittle or learn it directly on them. I think there I have to use an additional set of hardware to make it run. If you want to train a walking gait, you can find the link to my repository below, where I will provide further updates. Make sure to install all the necessary python libraries in the import section of the code. https://github.com/ger01d/opencat-gym
Reinforcement Learning - OpenCat Gym content media
7
24
1k
Gero
Mar 04, 2021
In Software
Hi there, a few weeks ago I've been working on the kinematic modeling of Nybble and was deriving gaits like walking climbing etc. with this method (see the other post "Kinematic Model"). The problem was, that without further physical description, the kinematic model is to idealistic. Normally Nybble shifts its weight and there will be some kind of momentum leading to unpredictable movements. Therefore I concentrated on extending the kinematic model with a physical description in a simulation environment called pybullet. So first, let's take a look at the result: The model is based on an URDF File (Unified Robotics Description Format) which is a common file format that can be implemented in different simulation environments. Please take a closer look at the attached URDF-file for more information. It's mostly self explanatory. One Note: Masses, inertia, friction damping and so on are a first estimation and certainly not correct. If you have better data, please update the information in the URDF-file and upload it to the forum. I copied the walking gait from the instincts.h into the environment and controlled the position of the joints and links to make Nybble walk. This makes it interesting to test new gaits before implementing it on Nybble and creates many more possibilities. To make it run, you will have to install pybullet via python pip and also the bullet environment. Please see the homepage for further details: https://pybullet.org/wordpress/ Here's the code for the pybullet simulation: And this is the necessary URDF-file: (Please rename to nybble.urdf.I couldn't upload it with an URDF ending.) I will provide further code updates on: https://github.com/ger01d/dynamic-model-opencat
Dynamic Model of Nybble content media
6
7
277
Gero
Feb 02, 2021
In Software
Creating gaits, especially walking, trotting etc. is quite a challenging task, if you do this manually. It is therefore favorable to have a kinematic model of our cat. I wanted to show you my approach to create a new gait via Inverse Kinematics, where I'm using the IKPY library (https://github.com/Phylliade/ikpy). Inverse kinematics at a glance is that you provide a point in space and the angles of the motors are calculated. In IKPY this is achieved by creating "chains" e.g. upper_arm--lower_arm--paw. Then you decide where to place the paw in space. Below you can see an image of Nybbles Kinematic model, to give you a first impression. For the first tests I created an alternative walking gait that follows as swing-stance-pattern of this form: # Walking pattern (1 == swing) # [0,0,0,0,0, 0,0,0,0,0, 0,0,0,0,0, 1,1,1,1,1], # LL # [0,0,0,0,0, 1,1,1,1,1, 0,0,0,0,0, 0,0,0,0,0], # RL # [0,0,0,0,0, 0,0,0,0,0, 1,1,1,1,1, 0,0,0,0,0], # LA # [1,1,1,1,1, 0,0,0,0,0, 0,0,0,0,0, 0,0,0,0,0], # RA The longitudinal movement (blue) and the lift (orange) is based on sine/cosine-functions, that follow the pattern phase shift as shown above. This pattern in combination with the IK-model will lead to this movement: I also tried this new gait on Nybble for validation and it works quite well. The lift is 1 cm in amplitude, so Nybble can now step over a small obstacle. Further updates and the Bittle-Version can be found here: https://github.com/ger01d/kinematic-model-opencat So here's the code for the version above: import ikpy from ikpy.chain import Chain from ikpy.link import OriginLink, URDFLink import numpy as np from numpy import sin, cos, pi import matplotlib.pyplot as plt import mpl_toolkits.mplot3d.axes3d as p3 deg2rad = pi/180 # Values in cm armLength = 5 bodyLength = 12 bodyWidth = 10 distanceFloor = 7 stepLength = 5 swingHeight = 1 leanLeft = 0 # Not working, yet leanRight = -leanLeft # Not working, yet leanForward = 0 # cm left_arm = Chain(name='left_arm', links=[ URDFLink( name="center", translation_vector=[leanForward, 0, distanceFloor], orientation=[0, 0, 0], rotation=[0, 0, 0], ), URDFLink( name="shoulder", translation_vector=[0, bodyWidth/2, leanLeft], orientation=[0, 0, 0], rotation=[0, 1, 0], bounds=(0.1*deg2rad, 179*deg2rad), ), URDFLink( name="upperArm", translation_vector=[armLength, 0, 0 ], orientation=[0, 0, 0], rotation=[0, 1, 0], bounds=(-179*deg2rad, -0.1*deg2rad), ), URDFLink( name="lowerArm", translation_vector=[armLength, 0, 0], orientation=[0, 0, 0], rotation=[0, 0, 0], ) ]) right_arm = Chain(name='right_arm', links=[ URDFLink( name="center", translation_vector=[leanForward, 0, distanceFloor], orientation=[0, 0, 0], rotation=[0, 0, 0], ), URDFLink( name="shoulder", translation_vector=[0, -bodyWidth/2, leanRight], orientation=[0, 0, 0], rotation=[0, 1, 0], bounds=(0.1*deg2rad, 179*deg2rad), ), URDFLink( name="upperArm", translation_vector=[armLength, 0, 0], orientation=[0,0,0], rotation=[0,1,0], bounds=(-179*deg2rad, -1*deg2rad), ), URDFLink( name="lowerArm", translation_vector=[armLength, 0, 0 ], orientation=[0,0,0], rotation=[0, 1, 0], ) ]) left_leg = Chain(name='left_leg', links=[ URDFLink( name="center", translation_vector=[leanForward, 0, distanceFloor], orientation=[0, 0, 0], rotation=[0, 0, 0], ), URDFLink( name="butt", translation_vector=[-bodyLength, 0, 0], orientation=[0, 0, 0], rotation=[0, 0, 0], ), URDFLink( name="hip", translation_vector=[0, bodyWidth/2, leanLeft], orientation=[0, 0, 0], rotation=[0, 1, 0], bounds=(0.1*deg2rad, 100*deg2rad), ), URDFLink( name="upperLeg", translation_vector=[armLength, 0, 0 ], orientation=[0, 0, 0], rotation=[0, 1, 0], bounds=(1*deg2rad, 179*deg2rad), ), URDFLink( name="lowerLeg", translation_vector=[armLength, 0, 0 ], orientation=[0, 0, 0], rotation=[0, 1, 0], ) ]) right_leg = Chain(name='right_leg', links=[ URDFLink( name="center", translation_vector=[leanForward, 0, distanceFloor], orientation=[0, 0, 0], rotation=[0, 0, 0], ), URDFLink( name="butt", translation_vector=[-bodyLength, 0, 0], orientation=[0, 0, 0], rotation=[0, 0, 0], ), URDFLink( name="hip", translation_vector=[ 0, -bodyWidth/2, leanRight], orientation=[0, 0, 0], rotation=[0, 1, 0], bounds=(0.1*deg2rad, 100*deg2rad), ), URDFLink( name="upperLeg", translation_vector=[armLength, 0, 0 ], orientation=[0, 0, 0], rotation=[0, 1, 0], bounds=(1*deg2rad, 179*deg2rad), ), URDFLink( name="lowerLeg", translation_vector=[armLength, 0, 0], orientation=[0, 0, 0], rotation=[0, 1, 0], ) ]) def buildGait(frames): frame = np.arange(0,frames) swingEnd = pi/2 # longitudinalMovement swing = -cos(2*(frame*2*pi/frames)) stance = cos(2/3*(frame*2*pi/frames-swingEnd)) swingSlice = np.less_equal(frame,swingEnd/(2*pi/frames)) stanceSlice = np.invert(swingSlice) longitudinalMovement = np.concatenate((swing[swingSlice], stance[stanceSlice])) longitudinalMovement = np.concatenate((longitudinalMovement,longitudinalMovement,longitudinalMovement, longitudinalMovement)) # verticalMovement lift = sin(2*(frame*2*pi/frames)) liftSlice = swingSlice verticalMovement = np.concatenate((lift[liftSlice], np.zeros(np.count_nonzero(stanceSlice)))) verticalMovement = np.concatenate((verticalMovement, verticalMovement, verticalMovement, verticalMovement)) return longitudinalMovement, verticalMovement frames = 43 longitudinalMovement, verticalMovement = buildGait(frames) # Walking pattern # [0,0,0,0,0, 0,0,0,0,0, 0,0,0,0,0, 1,1,1,1,1], # LL # [0,0,0,0,0, 1,1,1,1,1, 0,0,0,0,0, 0,0,0,0,0], # RL # [0,0,0,0,0, 0,0,0,0,0, 1,1,1,1,1, 0,0,0,0,0], # LA # [1,1,1,1,1, 0,0,0,0,0, 0,0,0,0,0, 0,0,0,0,0], # RA # Phase shift between arms/legs, [RA, RL, LA, LL] shiftFrame = np.round(np.array([0, pi/2, pi, 3*pi/2])/2/pi*frames) shiftFrame = shiftFrame.astype(int) for frame in range(0, frames): right_arm_angles = 180/pi*right_arm.inverse_kinematics(target_position = np.array([stepLength*longitudinalMovement[frame], -bodyWidth/2 ,swingHeight*verticalMovement[frame]])) right_arm_correction = np.array([0, -90, 90, 0]) right_arm_angles = np.round(right_arm_angles+right_arm_correction) right_arm_angles = np.delete(right_arm_angles, np.s_[0,3], axis=0) right_arm_angles = right_arm_angles.astype(int) right_leg_angles = 180/pi*right_leg.inverse_kinematics(target_position = np.array([-bodyLength+stepLength*longitudinalMovement[frame+shiftFrame[1]], -bodyWidth/2 , swingHeight*verticalMovement[frame+shiftFrame[1]]])) right_leg_correction = np.array([0, 0, -90, -90, 0]) right_leg_angles = np.round(right_leg_angles+right_leg_correction) right_leg_angles = np.delete(right_leg_angles, np.s_[0,1,4], axis=0) right_leg_angles = right_leg_angles.astype(int) left_arm_angles = 180/pi*left_arm.inverse_kinematics(target_position = np.array([stepLength*longitudinalMovement[frame+shiftFrame[2]], +bodyWidth/2 , swingHeight*verticalMovement[frame+shiftFrame[2]]])) left_arm_correction = np.array([0, -90, 90, 0]) left_arm_angles = np.round(left_arm_angles+left_arm_correction) left_arm_angles = np.delete(left_arm_angles, np.s_[0,3], axis=0) left_arm_angles = left_arm_angles.astype(int) left_leg_angles = 180/pi*left_leg.inverse_kinematics(target_position = np.array([-bodyLength+stepLength*longitudinalMovement[frame+shiftFrame[3]], +bodyWidth/2 , swingHeight*verticalMovement[frame+shiftFrame[3]]])) left_leg_correction = np.array([0, 0, -90, -90, 0]) left_leg_angles = np.round(left_leg_angles+left_leg_correction) left_leg_angles = np.delete(left_leg_angles, np.s_[0,1,4],axis=0) left_leg_angles = left_leg_angles.astype(int) # Writing sequence to file gait_sequence = np.concatenate((left_arm_angles, right_arm_angles, right_leg_angles, left_leg_angles)) print(frame," ",gait_sequence) f = open("gait_sequence.csv", "a") f.write("#") np.savetxt(f, gait_sequence[[0,2,4,6,1,3,5,7]], fmt='%3.1i', delimiter=',', newline=", ") f.write("+") f.write("\n") f.close() # Create plot and image for each frame fig = plt.figure() ax = p3.Axes3D(fig) ax.set_box_aspect([3, 3/2,1]) ax.set_xlim3d([-20, 10]) ax.set_xlabel('X') ax.set_ylim3d([-10, 10]) ax.set_ylabel('Y') ax.set_zlim3d([0.0, 10]) ax.set_zlabel('Z') right_arm.plot(right_arm.inverse_kinematics(target_position = np.array([stepLength*longitudinalMovement[frame], -bodyWidth/2 ,swingHeight*verticalMovement[frame]])), ax) right_leg.plot(right_leg.inverse_kinematics(target_position = np.array([-bodyLength+stepLength*longitudinalMovement[frame+shiftFrame[1]], -bodyWidth/2 , swingHeight*verticalMovement[frame+shiftFrame[1]]])), ax) left_arm.plot(left_arm.inverse_kinematics(target_position = np.array([stepLength*longitudinalMovement[frame+shiftFrame[2]], +bodyWidth/2 , swingHeight*verticalMovement[frame+shiftFrame[2]]])), ax) left_leg.plot(left_leg.inverse_kinematics(target_position = np.array([-bodyLength+stepLength*longitudinalMovement[frame+shiftFrame[3]], +bodyWidth/2 , swingHeight*verticalMovement[frame+shiftFrame[3]]])), ax) figureName = "Nybble_" + str(frame) plt.savefig(figureName) #plt.show()
Kinematic Model of Nybble and Bittle content media
12
54
2k
Gero
Jan 23, 2021
In Software
Hi there, recently I implemented the ultrasonic sensor (see my other post: "Protothreading") and established a serial connection via PySerial and Bluetooth to communicate with Nybble (see my post "Make Nybble do random stuff"). The problem was, that Nybble would run eventually into obstacles and you had to pay attention on it. Therefore I extended the code with a simple algorithm, that based on coincidence and the distance from the ultrasonic sensor avoids obstacles (certainly not the most efficient way, but somehow catty). I think this can be a good starting point to implement more complicated (and better) algorithms for obstacle avoidance. I'm looking forward on your implementations and variations. One warning: There are still many situations where the ultrasonic sensor could fail (e.g. sharp angles with the wall), so pay attention on what Nybble is doing, and avoid trotting. So here's the python code: import time import serial import random import asyncio from math import fsum # Establish serial connection via PySerial ser = serial.Serial( port='/dev/rfcomm0', # Change according to your port baudrate=115200, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, bytesize=serial.EIGHTBITS, timeout=1 ) catStuff = ['kwkF', 'ksit', 'khi', 'kbuttUp', 'kpee'] weights = [10, 20, 5, 5, 5] # Increase chance with higher values avoidanceManeuvers = ['kwkL', 'kwkR'] # Define asynchronous tasks async def randomMovement(): while True: currentAction = random.choices(catStuff, weights, k=1) ser.write(str.encode(currentAction[0])) ser.reset_input_buffer() await asyncio.sleep(random.random()*20) async def avoidObstacles(): while True: distance = await checkDistance() if ((distance[0] and distance[1]) > 1.0): print(distance) criticalDistance = fsum(distance)/2 if ((20.1 < criticalDistance < 80.0) and (distance[1] < distance[0]*1.03)): ser.write(str.encode(random.choice(avoidanceManeuvers))) await asyncio.sleep(random.random()*3) elif (0.0 < criticalDistance < 20): ser.write(str.encode('kbk')) await asyncio.sleep(random.random()*3) elif ((criticalDistance >= 80.0) and (distance[1]*1.03 > distance[0])): ser.write(str.encode('kwkF')) await asyncio.sleep(random.random()*3) async def checkDistance(): try: distanceT1 = float(ser.readline().decode("ascii")) ser.reset_input_buffer() await asyncio.sleep(0.5) distanceT2 = float(ser.readline().decode("ascii")) except: distanceT1 = 0 distanceT2 = 0 return distanceT1, distanceT2 # Initialize Nybble time.sleep(10) ser.write(str.encode('kbalance')) time.sleep(2) ser.reset_input_buffer() # Create Nybble loop nybble = asyncio.get_event_loop() asyncio.ensure_future(checkDistance()) asyncio.ensure_future(randomMovement()) asyncio.ensure_future(avoidObstacles()) nybble.run_forever()
9
17
526
Gero
Jan 20, 2021
In Software
Hi there, For those of you, who are using the Bluetooth-module I wrote some lines to make Nybble do random stuff within random time intervals. All the actions are send from the computer via Python PySerial and give "life" to Nybble. The next step is to read out the ultrasonic sensor via the serial port and implement obstacles avoidance. I already implemented the ultrasonic sensor via protothreading (see my other post named Protothreading) without losing movement performance. The serial port would be a substitution of the Raspberry Pi as a "Brain" and might be more efficient concerning battery usage. Make sure to set up the correct serial port in the code. import time import serial import random # Establish serial connection via PySerial ser = serial.Serial( port='/dev/rfcomm0', # Change according to your port baudrate=115200, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, bytesize=serial.EIGHTBITS, timeout=1 ) catStuff = ['kbalance', 'kwkF', 'kwkF', 'kwkF', 'kwkL','kwkR', 'ksit', 'khi', 'kbuttUp', 'kpee', 'd', 'd', 'd', 'kbk', 'klu'] time.sleep(10) currentAction = 'kbalance' while(True): ser.write(str.encode(currentAction)) currentAction = random.choice(catStuff) time.sleep(random.random()*20)
2
3
204
Gero
Jan 20, 2021
In Software
Hi there, Since Nybble stutters a lot when the gyro is activated, I implemented the protothreading.h library. Instead of the delay() action, PT_SLEEP() can be used, without stopping the microcontroller. This makes the movement more fluent and speeds up Nybble in gyro mode. I also implemented the ultrasonic sensor as a protothread, so the distance can be calculated without delay. Please review the code (certainly not perfect yet) and share your experience. To use protothreads, you have to install the protothread library in the Arduino-IDE (Tools --> Manage Libraries). Ultrasonic Sensor: #include "protothreads.h" /* Protothreads: Thanks to Scott Fitzgerald, Arturo Guadalupi, Colby Newman and Ben Artin */ pt ptUltra; int ultraThread(struct pt* pt) { static int duration = 0; static float distance = 0.0; static float farTime = LONGEST_DISTANCE*2/0.034; PT_BEGIN(pt); // Loop forever for(;;) { digitalWrite(TRIGGER, LOW); // turn the LED on (HIGH is the voltage level) PT_SLEEP(pt, 2e-3); digitalWrite(TRIGGER, HIGH); // turn the LED off by making the voltage LOW PT_SLEEP(pt, 10e-3); digitalWrite(TRIGGER, LOW); // Reads the echoPin, returns the sound wave travel time in microseconds duration = pulseIn(ECHO, HIGH, farTime); // Calculating the distance distance = duration * 0.034 / 2; // 10^-6 * 34000 cm/s PTL(distance); PT_SLEEP(pt, 500); } PT_END(pt); } BodyMotion Thread pt ptBodyMotion; int checkBodyMotionThread(struct pt* pt) { static byte hold = 0; PT_BEGIN(pt); // Loop forever for(;;) { //if (!dmpReady) return; getYPR(); // -- //deal with accidents if (fabs(ypr[1]) > LARGE_PITCH || fabs(ypr[2]) > LARGE_ROLL) {//wait until stable if (!hold) { getYPR(); PT_SLEEP(pt, 10); } if (fabs(ypr[1]) > LARGE_PITCH || fabs(ypr[2]) > LARGE_ROLL) {//check again if (!hold) { token = 'k'; if (fabs(ypr[2]) > LARGE_ROLL) { strcpy(newCmd, "rc"); newCmdIdx = 4; } else { strcpy(newCmd, ypr[1] < LARGE_PITCH ? "lifted" : "dropped"); newCmdIdx = 1; } } hold = 10; } } // recover else if (hold) { if (hold == 1) { token = 'k'; strcpy(newCmd, "balance"); newCmdIdx = 1; } hold --; if (!hold) { char temp[CMD_LEN]; strcpy(temp, newCmd); strcpy(newCmd, lastCmd); strcpy(lastCmd, temp); newCmdIdx = 1; meow(); } } //calculate deviation for (byte i = 0; i < 2; i++) { RollPitchDeviation[i] = ypr[2 - i] - motion.expectedRollPitch[i]; //all in degrees //PTL(RollPitchDeviation[i]); RollPitchDeviation[i] = sign(ypr[2 - i]) * max(fabs(RollPitchDeviation[i]) - levelTolerance[i], 0);//filter out small angles } PT_SLEEP(pt, 5); } //PTL(jointIdx); PT_END(pt); } Don't forget to add those lines in setup() PT_INIT(&ptUltra); PT_INIT(&ptBodyMotion); And to call the threads regularly in the main loop() PT_SCHEDULE(ultraThread(&ptUltra)); PT_SCHEDULE(checkBodyMotionThread(&ptBodyMotion));
2
34
666

Gero

More actions
bottom of page