challenge_robotique_si_brestois.pdf
Chaque département de R&D doit apporter une réponse permettant d'équipper 2 RobotGolf, un Robot 'Shooter' et un Robot 'Pusher'.
Alimentation en 12V, 7V et 5V.
L'électroaimant consomme j'usqu'à 9A. Lors de son alimentation, il ne faut pas écrouler l'alimentation de l'Arduino. (Risque de reset)
Il faut prévoir le nombres de matchs réalisable avec 1 charge de batterie.
Utilisation de blocs batteries 11,1V disponibles en 5 exemplaires.
Utilisation d'un convertisseur 11,1V vers 7V (6V moteurs + 0,7V diode anti retour).
Utilisation du convertisseur 7V vers 5V du pont en H pour alimenter la cartes arduino et ses capteurs.
La diode de roue libre permet de libérer l'énergie accumulée dans le solénoïde après un shoot. (Lors de la formation du champ magnétique)
La seconde diode permet de ne pas utiliser l'énergie accumulée dans le condensateur pour l'action du solénoïde. (Prévention contre les resets intepestifs de la carte arduino lors d'un shoot)
Il faut fournir 2 plateformes issues du matériel disponible dans les armoires du labo SI.
Il faut aussi mutualiser le code Arduino.
La bibliothèque AFmotor permet de gérer la MotorShield V1 AFmotor.h adafruit_motor_shield_library-1.0.1.zip
Une plateforme à 4 roues standards et une plateforme à 4 rous suédoises (mecanum).
Pour marquer des points, il faut utiliser un smartphone. C-à-d, développer une application iOS/Androïd. Il est important ici aussi de mutualiser les développents pour les 2 robots.
Utilisation d'un module Bluetooth avec une télécommande sur smartphone avec RemoteXY
Création d'une commande bluetooth avec 5 widgets maximum pour la version gratuite. (10€/an en version Pro)
Le code de base se récupère sur le site remotexy. Il faut ajouter la bibliothèque remotexy.zip dans l'IDE Arduino.
Proposer une structure fixe (Club) pour le Robot 'Pusher' répondant au cahier des charges.
Proposer une structure mécanique pour le Robot 'Shooter'.
Comment régle-t-on la puissance du shoot dans les deux cas?
Les élèves proposent un système de visée laser.
Quelles sont les contraintes apportées aux autres équipes ?
Utilisation d'un servo moteur pour régler la visée. L'objectif est de positionner correctement le robot pour viser l'objectif.
Implémenter une sécurité afin d'éviter de diriger le laser vers les yeux des spectateurs.
Définir un système de décoration des 2 platteformes permettant de respecter la thématique 'Golf'.
Là encore il faut mutualiser les développements. Attention au dimentions et au besoin de place pour le mouvement mécanique du Robot 'Shooter'.
Veiller à bien remettre à jour la déclaration de RemoteXY_CONF[] après chaque mise à jour de la télécommande.
Une structure logicielle permettant l'intégration rapide des codes des différentes équipes. Mais interdisant l'utilisation de la fonction Delay() ainsi que des fonctions bloquantes.
/*
-- RobotGolf_II --
This source code of graphical user interface
has been generated automatically by RemoteXY editor.
To compile this code using RemoteXY library 3.1.8 or later version
download by link http://remotexy.com/en/library/
To connect using RemoteXY mobile app by link http://remotexy.com/en/download/
- for ANDROID 4.11.1 or later version;
- for iOS 1.9.1 or later version;
This source code is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
*/
//////////////////////////////////////////////
// RemoteXY include library //
//////////////////////////////////////////////
// RemoteXY select connection mode and include library
#define REMOTEXY_MODE__HARDSERIAL
#include <RemoteXY.h>
// RemoteXY connection settings
#define REMOTEXY_SERIAL Serial3
#define REMOTEXY_SERIAL_SPEED 9600
// RemoteXY configurate
#pragma pack(push, 1)
uint8_t RemoteXY_CONF[] = // 105 bytes
{ 255,6,0,0,0,98,0,16,31,2,5,53,10,7,38,38,6,36,35,35,
2,26,31,1,0,61,20,16,16,32,10,12,12,1,31,70,105,114,101,0,
4,32,83,2,15,60,48,3,14,71,2,26,2,1,57,51,22,11,39,81,
22,11,2,26,31,31,83,108,111,119,0,70,97,115,116,0,2,1,5,51,
45,11,3,80,27,12,2,26,31,31,77,101,99,97,110,117,109,0,78,111,
114,109,97,108,0 };
// this structure defines all the variables and events of your control interface
struct {
// input variables
int8_t pad_x; // from -100 to 100
int8_t pad_y; // from -100 to 100
uint8_t fire; // =1 if button pressed, else =0
int8_t angleLaser; // =-100..100 slider position
uint8_t speed; // =1 if switch ON and =0 if OFF
uint8_t mecanum; // =1 if switch ON and =0 if OFF
// other variable
uint8_t connect_flag; // =1 if wire connected, else =0
} RemoteXY;
#pragma pack(pop)
/////////////////////////////////////////////
// END RemoteXY include //
/////////////////////////////////////////////
#define PIN_FIRE 19
// TODO you initialise code
#include "fire.h"
#include "laser.h"
#include "motion.h"
//
void setup()
{
RemoteXY_Init ();
pinMode (PIN_FIRE, OUTPUT);
// TODO you setup code
Serial.begin(9600);
setupLaser();
setupMotion();
setupFire();
}
void loop()
{
RemoteXY_Handler ();
// TODO you loop code
// use the RemoteXY structure for data transfer
// do not call delay()
loopLaser();
loopMotion();
loopFire();
}
#ifndef __ROBOTGOLF_FIRE_H__
#define __ROBOTGOLF_FIRE_H__
#include <Arduino.h>
void setupFire() {
Serial.println("Fire initialised.");
}
void loopFire() {
// digitalWrite(PIN_FIRE, (RemoteXY.fire==0)?LOW:HIGH);
if (RemoteXY.fire) {
digitalWrite(PIN_FIRE, HIGH);
if(RemoteXY.speed) {
delay(30);
} else {
delay(100);
}
digitalWrite(PIN_FIRE, LOW);
}
while(RemoteXY.fire) {
RemoteXY_Handler ();
}
}
#endif
#ifndef __ROBOTGOLF_LASER_H__
#define __ROBOTGOLF_LASER_H__
#include <Arduino.h>
#include <Servo.h>
Servo myservo;
#define PIN_ANGLE_LASER 10
void setupLaser() {
myservo.attach(PIN_ANGLE_LASER); // attaches the servo on pin PIN_ANGLE_LASER to the servo object
Serial.println("Laser initialised.");
}
void loopLaser() {
int _position=map(RemoteXY.angleLaser, -100, 100, 45, 90);
myservo.write(_position);
// Serial.print("Angle Laser = ");
// Serial.println(_position);
}
#endif
#ifndef __ROBOTGOLF_MOTION_H__
#define __ROBOTGOLF_MOTION_H__
#define __MOTION_DEBUG_ false
#include <Arduino.h>
#include <AFMotor.h>
//Constants
const int slowSpeed=150;
const int fastSpeed=250;
//Parameters
AF_DCMotor motorFrontLeft(1);
AF_DCMotor motorFrontRight(2);
AF_DCMotor motorBackLeft(3);
AF_DCMotor motorBackRight(4);
int motorFrontLeftSpeed = 0;
int motorFrontRightSpeed = 0;
int motorBackLeftSpeed = 0;
int motorBackRightSpeed = 0;
// int motorBackLeftSpeed = 0;
// int motorBackRightSpeed = 0;
// int motorFrontLeftSpeed = 0;
// int motorFrontRightSpeed = 0;
void setupMotion() {
motorFrontLeft.setSpeed(0);
motorFrontLeft.run(RELEASE);
motorFrontRight.setSpeed(0);
motorFrontRight.run(RELEASE);
motorBackLeft.setSpeed(0);
motorBackLeft.run(RELEASE);
motorBackRight.setSpeed(0);
motorBackRight.run(RELEASE);
Serial.println("Motors initialised.");
}
void loopMotion() {
int joystickXValue = 0;
int joystickYValue = 0;
if(RemoteXY.speed) {
joystickXValue = map(RemoteXY.pad_x,-100,100,-128,128);
joystickYValue = map(RemoteXY.pad_y,-100,100,-128,128);
} else {
joystickXValue = map(RemoteXY.pad_x,-100,100,-255,255);
joystickYValue = map(RemoteXY.pad_y,-100,100,-255,255);
}
if(RemoteXY.mecanum) {
// conversion des valeurs analogiques du joystick en vitesses pour les moteurs
motorBackLeftSpeed = joystickYValue - joystickXValue;
motorBackRightSpeed = joystickYValue + joystickXValue;
motorFrontLeftSpeed = motorBackLeftSpeed; // joystickYValue + joystickXValue;
motorFrontRightSpeed = motorBackRightSpeed; // joystickYValue - joystickXValue;
// limitation des vitesses maximale et minimale des moteurs
motorFrontLeftSpeed = constrain(motorFrontLeftSpeed, -255, 255);
motorFrontRightSpeed = constrain(motorFrontRightSpeed, -255, 255);
motorBackLeftSpeed = constrain(motorBackLeftSpeed, -255, 255);
motorBackRightSpeed = constrain(motorBackRightSpeed, -255, 255);
// envoi des vitesses aux moteurs
motorFrontLeft.setSpeed(abs(motorFrontLeftSpeed));
motorFrontRight.setSpeed(abs(motorFrontRightSpeed));
motorBackLeft.setSpeed(abs(motorBackLeftSpeed));
motorBackRight.setSpeed(abs(motorBackRightSpeed));
// inversion des directions des moteurs si nécessaire
if (motorFrontLeftSpeed < 0) {
motorFrontLeft.run(BACKWARD);
} else {
motorFrontLeft.run(FORWARD);
}
if (motorFrontRightSpeed < 0) {
motorFrontRight.run(BACKWARD);
} else {
motorFrontRight.run(FORWARD);
}
if (motorBackLeftSpeed < 0) {
motorBackLeft.run(BACKWARD);
} else {
motorBackLeft.run(FORWARD);
}
if (motorBackRightSpeed < 0) {
motorBackRight.run(BACKWARD);
} else {
motorBackRight.run(FORWARD);
}
} else {
// conversion des valeurs analogiques du joystick en vitesses pour les moteurs
motorFrontLeftSpeed = joystickYValue + joystickXValue;
motorFrontRightSpeed = joystickYValue - joystickXValue;
motorBackLeftSpeed = joystickYValue - joystickXValue;
motorBackRightSpeed = joystickYValue + joystickXValue;
// limitation des vitesses maximale et minimale des moteurs
motorFrontLeftSpeed = constrain(motorFrontLeftSpeed, -255, 255);
motorFrontRightSpeed = constrain(motorFrontRightSpeed, -255, 255);
motorBackLeftSpeed = constrain(motorBackLeftSpeed, -255, 255);
motorBackRightSpeed = constrain(motorBackRightSpeed, -255, 255);
// envoi des vitesses aux moteurs
motorFrontLeft.setSpeed(abs(motorFrontLeftSpeed));
motorFrontRight.setSpeed(abs(motorFrontRightSpeed));
motorBackLeft.setSpeed(abs(motorBackLeftSpeed));
motorBackRight.setSpeed(abs(motorBackRightSpeed));
// inversion des directions des moteurs si nécessaire
if (motorFrontLeftSpeed < 0) {
motorFrontLeft.run(BACKWARD);
} else {
motorFrontLeft.run(FORWARD);
}
if (motorFrontRightSpeed < 0) {
motorFrontRight.run(BACKWARD);
} else {
motorFrontRight.run(FORWARD);
}
if (motorBackLeftSpeed < 0) {
motorBackLeft.run(BACKWARD);
} else {
motorBackLeft.run(FORWARD);
}
if (motorBackRightSpeed < 0) {
motorBackRight.run(BACKWARD);
} else {
motorBackRight.run(FORWARD);
}
}
}
#endif
Pièce | Fichier | Notes |
---|---|---|
![]() |
fixation_laser.zip | Pièce à fixer au dessus de l'électroaimant. |
![]() |
club_golf.zip | Pièce à fixer à l'extrémité de l'électroaimant. |
![]() |
fixation_mcc.zip | Fixation pour les moteur MCC 1:48 |
![]() |
fixation120_mcc.zip | Fixation pour les moteur MCC 1:48 avec fraisage |