diff --git a/include/.gitkeep b/include/.gitkeep new file mode 100644 index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391 diff --git a/lib/LiquidCrystal_I2C-1.1.3/LiquidCrystal_I2C.cpp b/lib/LiquidCrystal_I2C-1.1.3/LiquidCrystal_I2C.cpp index 79f43894fefa3b7c0b3afe4530497baddebc23d8..87b1b09e0efab56abc76757e5e5848832e14dd94 100644 --- a/lib/LiquidCrystal_I2C-1.1.3/LiquidCrystal_I2C.cpp +++ b/lib/LiquidCrystal_I2C-1.1.3/LiquidCrystal_I2C.cpp @@ -58,7 +58,6 @@ void LiquidCrystal_I2C::init(){ void LiquidCrystal_I2C::init_priv() { - Wire.begin(); _displayfunction = LCD_4BITMODE | LCD_1LINE | LCD_5x8DOTS; begin(_cols, _rows); } diff --git a/src/main.cpp b/src/main.cpp index 0b81865d603f858e3b7d7ff9a98540534bb53131..3815bf4f880a376fccbac16df92f7d072fbf6244 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -13,8 +13,10 @@ #include <std_msgs/Bool.h> #include <std_msgs/Int32.h> #include <geometry_msgs/Vector3.h> +#include <ctrlpan_msgs/alim_stat.h> + + -// color sensors #define COL_L 4 #define COL_R 7 Adafruit_TCS34725 tcs = Adafruit_TCS34725(TCS34725_INTEGRATIONTIME_24MS, TCS34725_GAIN_1X); @@ -22,6 +24,7 @@ ros::NodeHandle node_handle; geometry_msgs::Vector3 hsv_msg; + // Servo object declaration Servo flagServo; #define FLAG_UNFOLDED_ANGLE 170 @@ -31,6 +34,11 @@ Servo armServo; //pour manche à air #define ARM_UNFOLDED_ANGLE 90 #define ARM_FOLDED_ANGLE 0 +// I2C : (if not working : try inverse sda and scl pin) +// todo : remove nucleo jumpers to use these pins. +#define I2C_SDA A5 +#define I2C_SCL A4 + // Pin declaration const int flagServoPin = D6; const int armServoPin = D4; @@ -91,6 +99,7 @@ std_msgs::Bool teamMsg; std_msgs::Bool buttonStatusMsg; std_msgs::Bool pullCordStatusMsg; std_msgs::Bool bauStatusMsg; +ctrlpan_msgs::alim_stat alimStatMsg; ros::Publisher teamStatusPub("team", &teamMsg); ros::Publisher buttonStatusPub("button_status", &buttonStatusMsg); @@ -98,6 +107,7 @@ ros::Publisher bauStatusPub("BAU_status", &bauStatusMsg); ros::Publisher pullCordStatusPub("pull_cord_status", &pullCordStatusMsg); ros::Publisher color_sensor_left("color_sensor/left", &hsv_msg); ros::Publisher color_sensor_right("color_sensor/right", &hsv_msg); +ros::Publisher alimStatPub("alim_stat", &alimStatMsg); void TCA9548A(uint8_t bus) @@ -108,6 +118,7 @@ void TCA9548A(uint8_t bus) } + void estimatedScoreCallback(const std_msgs::Int32 &estimatedScore); ros::Subscriber<std_msgs::Int32> estimatedScoreSub("estimated_score", &estimatedScoreCallback); @@ -164,9 +175,17 @@ void setupColorSensors(){ void setup() { + + // INIT Wire on : A4 => SDA || A5 => SCL + Wire.begin(I2C_SDA, I2C_SCL); + + flagServo.attach(flagServoPin); flagServo.write(0); + armServo.attach(armServoPin); + armServo.write(0); + pinMode(pullCordPin, INPUT_PULLUP); pinMode(switchPin, INPUT_PULLUP); pinMode(buttonPin, INPUT_PULLUP); @@ -189,9 +208,11 @@ void setup() nh.advertise(buttonStatusPub); nh.advertise(pullCordStatusPub); nh.advertise(bauStatusPub); + nh.advertise(alimStatPub); nh.subscribe(estimatedScoreSub); nh.subscribe(flagStatusSub); + nh.subscribe(armStateSub); nh.subscribe(bauSoftSub); // color Sensors setup @@ -249,6 +270,10 @@ void manage_supply_card_data(){ float curr5_value = (float) curr5_valueADC * CURR5_RATIO; float curr12_value = (float) curr12_valueADC * CURR12_RATIO; + alimStatMsg.voltage_12 = volt12_value; + alimStatMsg.voltage_5 = volt5_value; + alimStatMsg.current_12 = curr12_value; + alimStatMsg.current_5 = curr5_value; } @@ -318,6 +343,7 @@ void colorSensorsLoop(){ void loop() { + // TODOOOOOOO : CHANGE if (!nh.connected()) { @@ -396,6 +422,8 @@ void loop() bauStatusMsg.data = bauStatus; bauStatusPub.publish(&bauStatusMsg); + manage_supply_card_data(); + alimStatPub.publish(&alimStatMsg); lastMessageTime = millis(); nh.spinOnce();