Skip to content

Commit 9f24fd4

Browse files
committed
* New structure in definition.h so
* Changed how to enable/disable the different modules in the code. * Moved user-config from Liam.ino to definition.h * Merged Liam5_Setup_and_Debug into Liam and added a new SetupDebug mode. * Added SetupDebug for ADXL345
1 parent 60f947f commit 9f24fd4

File tree

4 files changed

+778
-460
lines changed

4 files changed

+778
-460
lines changed

Liam/Definition.cpp

+34-18
Original file line numberDiff line numberDiff line change
@@ -1,31 +1,47 @@
1-
/// This is the library for the defaults
2-
//
3-
// Changelog:
4-
// 2014-12-12 - Initial version by Jonas
1+
/*
2+
Definition.h is part of the project: liam - DIY Robot Lawn mover
53
6-
/* ============================================
7-
Placed under the GNU license
4+
Description: This file holds all configuration parameters, user specific,
5+
common and software specific parameters.
6+
7+
2017-06-06 Roberth Andersson:
8+
- Restructured the file and made differens sections of parameters. Added setup debug mode.
9+
2014-12-12 Jonas Forsell:
10+
- Initial version.
11+
12+
Copyright (c) 2017 Jonas Forsell (and team)
13+
14+
liam - DIY Robot LAwn mower is free software: you can redistribute it and/or modify
15+
it under the terms of the GNU General Public License as published by
16+
the Free Software Foundation, either version 3 of the License, or
17+
(at your option) any later version.
18+
19+
Foobar is distributed in the hope that it will be useful,
20+
but WITHOUT ANY WARRANTY; without even the implied warranty of
21+
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
22+
GNU General Public License for more details.
23+
24+
You should have received a copy of the GNU General Public License
25+
along with Foobar. If not, see <http://www.gnu.org/licenses/>.
826
9-
===============================================
1027
*/
1128

1229
#include "Definition.h"
1330

1431

15-
/** Define all pins
16-
*/
32+
/* Define all pins */
1733
void DEFINITION::definePinsInputOutput() {
18-
34+
1935
pinMode(WHEEL_MOTOR_A_CURRENT_PIN, INPUT);
2036
pinMode(WHEEL_MOTOR_B_CURRENT_PIN, INPUT);
2137
pinMode(SOC_PIN, INPUT);
2238
pinMode(CUTTER_CURRENT_PIN, INPUT);
23-
39+
2440
/* Some pins are better leave undefined as default
2541
pinMode(I2C_SDA_PIN, INPUT);
2642
pinMode(I2C_SDL_PIN, OUTPUT);
2743
28-
pinMode(RX_PIN, INPUT);
44+
pinMode(RX_PIN, INPUT);
2945
pinMode(TX_PIN, OUTPUT);
3046
*/
3147
pinMode(BWF_SENSOR_INPUT_PIN, INPUT);
@@ -34,23 +50,23 @@ void DEFINITION::definePinsInputOutput() {
3450
pinMode(DOCK_PIN, INPUT);
3551
pinMode(CUTTER_PWM_PIN, OUTPUT);
3652
pinMode(BWF_SELECT_B_PIN, OUTPUT);
37-
38-
#if defined __Bumper__
53+
54+
#if __Bumper__
3955
pinMode(BUMPER, INPUT);
4056
digitalWrite(BUMPER, HIGH);
4157
#else
4258
pinMode(BUMPER, OUTPUT);
4359
digitalWrite(BUMPER, LOW);
44-
#endif
60+
#endif
4561

46-
#if defined __Lift_Sensor__
62+
#if __Lift_Sensor__
4763
pinMode(LIFT_SENSOR_PIN, INPUT);
4864
digitalWrite(LIFT_SENSOR_PIN, HIGH);
4965
#else
5066
pinMode(LIFT_SENSOR_PIN, OUTPUT);
5167
digitalWrite(LIFT_SENSOR_PIN, LOW);
52-
#endif
53-
68+
#endif
69+
5470
pinMode(LED_PIN, OUTPUT);
5571
pinMode(WHEEL_MOTOR_B_PWM_PIN, OUTPUT);
5672
pinMode(WHEEL_MOTOR_A_DIRECTION_PIN, OUTPUT);

Liam/Definition.h

+165-106
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,33 @@
1-
// This is the definition for all the defaults
2-
//
1+
/*
2+
Definition.h is part of the project: liam - DIY Robot Lawn mover
33
4-
/* ============================================
5-
Placed under the GNU license
4+
Description: This file holds all configuration parameters, user specific,
5+
common and software specific parameters.
6+
7+
2017-06-06 Roberth Andersson:
8+
- Restructured the file and made differens sections of parameters.
9+
- Added setup debug mode.
10+
2014-12-12 Jonas Forsell:
11+
- Initial version.
12+
13+
Copyright (c) 2014-2017 Jonas Forsell (and team)
14+
15+
liam - DIY Robot LAwn mower is free software: you can redistribute it and/or modify
16+
it under the terms of the GNU General Public License as published by
17+
the Free Software Foundation, either version 3 of the License, or
18+
(at your option) any later version.
19+
20+
Foobar is distributed in the hope that it will be useful,
21+
but WITHOUT ANY WARRANTY; without even the implied warranty of
22+
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
23+
GNU General Public License for more details.
24+
25+
You should have received a copy of the GNU General Public License
26+
along with Foobar. If not, see <http://www.gnu.org/licenses/>.
627
7-
===============================================
828
*/
29+
30+
931
#include <Arduino.h>
1032
#include "Wheelmotor.h"
1133
#include "CutterMotor.h"
@@ -14,130 +36,167 @@ Placed under the GNU license
1436
#ifndef _DEFINITION_H_
1537
#define _DEFINITION_H_
1638

17-
const int NUMBER_OF_SENSORS = 3; // Number of BWF sensors can be 1-4 depending on shield
18-
19-
// Pin setup following Morgan 1.5 shield and up
20-
#define WHEEL_MOTOR_A_CURRENT_PIN 0
21-
#define WHEEL_MOTOR_B_CURRENT_PIN 1
22-
#define SOC_PIN 2
23-
#define CUTTER_CURRENT_PIN 3
24-
#define I2C_SDA_PIN 4
25-
#define I2C_SDL_PIN 5
26-
// Digital pins
27-
#define RX_PIN 0
28-
#define TX_PIN 1
29-
#define BWF_SENSOR_INPUT_PIN 2
30-
#define WHEEL_MOTOR_A_PWM_PIN 3
31-
#define BWF_SELECT_A_PIN 4
32-
#define DOCK_PIN 5
33-
#define CUTTER_PWM_PIN 6
34-
#define BWF_SELECT_B_PIN 7
35-
#define BUMPER 8
36-
#define LIFT_SENSOR_PIN 9
37-
#define LED_PIN 13
38-
#define WHEEL_MOTOR_B_PWM_PIN 11
39-
#define WHEEL_MOTOR_A_DIRECTION_PIN 12
40-
#define WHEEL_MOTOR_B_DIRECTION_PIN 13
41-
42-
// Cutter motor types
43-
#define BRUSHLESS 0
44-
#define BRUSHED 1
45-
#define NIDEC 2
46-
47-
// Battery
48-
#define LEADACID 0
49-
#define NIMH 1
50-
#define LIION 2
51-
52-
// Wheel motor
53-
#define WHEELMOTOR_OVERLOAD 130
54-
#define WHEELMOTOR_SMOOTHNESS 300
55-
56-
// If the mower has repeated overload within the interval below (in milliseconds), it will flag as having reached a bump.
57-
// It will then do some action as stated in the Controller.cpp file.
58-
#define OVERLOAD_INTERVAL 3000
39+
/* SETUP AND DEBUG MODE .
40+
First time you start your mover the code is configured to run in debug mode.
41+
In that mode you can send different commands to the mover to test different functions.
42+
You can also see some values reported by the sensors. You need probably to tweek some
43+
of the parameters in this file and when you are done remove or comment out this line to
44+
run your mover in real mode. */
45+
#define __SETUP_AND_DEBUG_MODE__ true
46+
47+
/******************************************************************
48+
User specific settings depends on how you have built your mover.
49+
*******************************************************************/
50+
51+
52+
/* Configure which Cutter motor you have.
53+
Types available:
54+
BRUSHLESS 0 (for all hobbyking motors with external ESC)
55+
BRUSHED: 1 (for all brushed motors, A3620 and NIDEC 22)
56+
NIDEC 2 (for NIDEC 24 or NIDEC 22 connected to morgan shield without any modifications) */
57+
const int MY_CUTTERMOTOR = 2;
58+
59+
/* Configure which type of battery you have.
60+
Types availible:
61+
LEADACID 0
62+
NIMH 1
63+
LIION 2
64+
*/
65+
const int MY_BATTERY = 2;
5966

60-
// CUTTER
61-
#define CUTTER_OVERLOAD 100
67+
/* Number of BWF sensors can be 1-4 depending on shield */
68+
const int NUMBER_OF_SENSORS = 2;
6269

63-
// Cutter states
64-
const int MOWING = 0;
65-
const int LAUNCHING = 1;
66-
const int DOCKING = 2;
67-
const int CHARGING = 3;
70+
/* BWF transmitter signals */
71+
#define INSIDE_BWF 5
72+
#define OUTSIDE_BWF 86
6873

69-
// Turning details
70-
#define TURN_INTERVAL 15000
71-
#define REVERSE_DELAY 2
72-
#define TURNDELAY 20 //Reduce for smaller turning angle
74+
/* If you have a bumper connected to pin8, set it to true. Remember to cut the brake connection on your motor shield */
75+
#define __Bumper__ false
7376

74-
// BWF Detection method (true = always, false = only at wire)
75-
#define BWF_DETECTION_ALWAYS true
76-
#define TIMEOUT 6000 //Time without signal before error
77+
/* If you have a lift sensor connection to front wheel (connected to pin9), set it to true */
78+
#define __Lift_Sensor__ false
7779

78-
// Trigger value for the mower to leave the BWF when going home
79-
// The higher value the more turns (in the same direction) the mower can make before leaving
80-
#define BALANCE_TRIGGER_LEVEL 10000
80+
/* Do you have a Sensor? If so, set one of these lines to true. */
81+
#define __MS5883L__ false
82+
#define __MS9150__ false
83+
#define __ADXL345__ true
8184

82-
// Code for inside and outside
83-
//#define INSIDE_BWF 103,4,103
84-
//#define OUTSIDE_BWF 103,107,103
85+
/* Tiltangle */
86+
#define TILTANGLE 45
8587

86-
// Version 2 of the BWF transmitter
87-
#define INSIDE_BWF 5
88-
#define OUTSIDE_BWF 86
88+
/* Flipangle (turn off cutter and stop everything) */
89+
#define FLIPANGLE 75
8990

90-
#define MAJOR_VERSION 4
91-
#define MINOR_VERSION_1 9
92-
#define MINOR_VERSION_2 1
91+
/* Do you have a Display? If so, set one of these lines to true. */
92+
#define __OLED__ false
93+
#define __LCD__ false
9394

94-
// If you have a bumper connected to pin8, uncomment the line below. Remember to cut the brake connection on your motor shield
95-
//#define __Bumper__
95+
/* Do you have a clock? If so, set it to true. */
96+
#define __RTC_CLOCK__ false
97+
#define GO_OUT_TIME 16, 00
98+
#define GO_HOME_TIME 22, 00
9699

97-
// If you have a lift sensor connection to front wheel (connected to pin9), uncomment this line
98-
//#define __Lift_Sensor__
100+
/* Motor Speeds */
101+
#define FULLSPEED 100
102+
#define SLOWSPEED 30
103+
#define CUTTERSPEED 100
99104

100-
// Do you have a Sensor? If so, uncomment one of these lines
101-
//#define __MS5883L__
102-
//#define __MS9150__
103-
//#define __ADXL345__
105+
/* Settings for ADXL345, what angle values the sensor reports when the mover is standing flat.
106+
IMPORTANT! You must calibrate those values for your setup.
107+
See the wiki:https://github.com/sm6yvr/liam/wiki/12.-Gyro-Accelerometer */
108+
/* Try to get inside for max x seconds, then stop and error. */
109+
#define Z_ANGLE_NORMAL 181
110+
#define Y_ANGLE_NORMAL 195
111+
112+
/* Enable this if you need the mower to go backward until it's inside and then turn.
113+
Default behavior is to turn directly when mower is outside BWF, if definition below is enabled this might help mower not to get stuck in slopes.
114+
If mower is not inside within x seconds mower will stop. */
115+
#define GO_BACKWARD_UNTIL_INSIDE false
116+
#define MAX_GO_BACKWARD_TIME 5
117+
118+
/******************************************************************
119+
Common settings that should be same for the most of us.
120+
*******************************************************************/
121+
/* Pin setup following Morgan 1.5 shield and up */
122+
/* Analog pins */
123+
#define WHEEL_MOTOR_A_CURRENT_PIN 0
124+
#define WHEEL_MOTOR_B_CURRENT_PIN 1
125+
#define SOC_PIN 2
126+
#define CUTTER_CURRENT_PIN 3
127+
#define I2C_SDA_PIN 4
128+
#define I2C_SDL_PIN 5
129+
/* Digital pins */
130+
#define RX_PIN 0
131+
#define TX_PIN 1
132+
#define BWF_SENSOR_INPUT_PIN 2
133+
#define WHEEL_MOTOR_A_PWM_PIN 3
134+
#define BWF_SELECT_A_PIN 4
135+
#define DOCK_PIN 5
136+
#define CUTTER_PWM_PIN 6
137+
#define BWF_SELECT_B_PIN 7
138+
#define BUMPER 8
139+
#define LIFT_SENSOR_PIN 9
140+
#define LED_PIN 13
141+
#define WHEEL_MOTOR_B_PWM_PIN 11
142+
#define WHEEL_MOTOR_A_DIRECTION_PIN 12
143+
#define WHEEL_MOTOR_B_DIRECTION_PIN 13
144+
145+
/******************************************************************
146+
Program settings that shold not be changed.
147+
*******************************************************************/
148+
149+
/* Cutter motor types */
150+
#define BRUSHLESS 0
151+
#define BRUSHED 1
152+
#define NIDEC 2
153+
154+
/* Battery */
155+
#define LEADACID 0
156+
#define NIMH 1
157+
#define LIION 2
158+
159+
/* Wheel motor */
160+
#define WHEELMOTOR_OVERLOAD 130
161+
#define WHEELMOTOR_SMOOTHNESS 300
104162

105-
// Do you have a Display? If so, uncomment one of these lines
106-
//#define __OLED__
107-
//#define __LCD__
163+
/* If the mower has repeated overload within the interval below (in milliseconds),
164+
it will flag as having reached a bump. It will then do some action as stated
165+
in the Controller.cpp file. */
166+
#define OVERLOAD_INTERVAL 3000
108167

109-
// Do you have a clock? If so, uncomment the line below
110-
//#define __RTC_CLOCK__
111-
#define GO_OUT_TIME 16, 00
112-
#define GO_HOME_TIME 22, 00
168+
/* CUTTER */
169+
#define CUTTER_OVERLOAD 100
113170

114-
// Tiltangle
115-
#define TILTANGLE 45
171+
/* Cutter states */
172+
const int MOWING = 0;
173+
const int LAUNCHING = 1;
174+
const int DOCKING = 2;
175+
const int CHARGING = 3;
116176

117-
// Flipangle (turn off cutter and stop everything)
118-
#define FLIPANGLE 75
177+
/* Turning details */
178+
#define TURN_INTERVAL 15000
179+
#define REVERSE_DELAY 2
180+
#define TURNDELAY 20 //Reduce for smaller turning angle
119181

120-
// Motor Speeds
121-
#define FULLSPEED 100
122-
#define SLOWSPEED 30
123-
#define CUTTERSPEED 100
182+
/* BWF Detection method (true = always, false = only at wire) */
183+
#define BWF_DETECTION_ALWAYS true
184+
/* Time without signal before error */
185+
#define TIMEOUT 6000
124186

125-
/* Settings for ADXL345, what angle values the sensor reports when the mover is standing flat.
126-
* IMPORTANT! You must calibrate those values for your setup, see the wiki:https://github.com/sm6yvr/liam/wiki/12.-Gyro-Accelerometer */
127-
#define Z_ANGLE_NORMAL 195
128-
#define Y_ANGLE_NORMAL 180
187+
/* Trigger value for the mower to leave the BWF when going home- The higher value
188+
the more turns (in the same direction) the mower can make before leaving */
189+
#define BALANCE_TRIGGER_LEVEL 10000
129190

130-
// Enable this if you need the mower to go backward until it's inside and then turn.
131-
// Default behavior is to turn directly when mower is outside BWF, if definition below is enabled this might help mower not to get stuck in slopes.
132-
// If mower is not inside within x seconds mower will stop.
133-
//#define GO_BACKWARD_UNTIL_INSIDE
134-
//#define MAX_GO_BACKWARD_TIME 5 // try to get inside for max x seconds, then stop and error.
191+
/* Software version */
192+
#define MAJOR_VERSION 5
193+
#define MINOR_VERSION_1 2
194+
#define MINOR_VERSION_2 0
135195

136196
class DEFINITION {
137197
public:
138198
void definePinsInputOutput();
139199
void setDefaultLevels(BATTERY* battery, WHEELMOTOR* left, WHEELMOTOR* right, CUTTERMOTOR* cutter);
140-
141200
private:
142201
};
143202

0 commit comments

Comments
 (0)