]> git.leonardobizzoni.com Git - pioneer-stm32/commitdiff
organize subfolders
authorFederica Di Lauro <federicadilauro1998@gmail.com>
Tue, 25 Feb 2020 10:36:20 +0000 (11:36 +0100)
committerFederica Di Lauro <federicadilauro1998@gmail.com>
Tue, 25 Feb 2020 10:36:20 +0000 (11:36 +0100)
otto_controller/.cproject
otto_controller/Core/Inc/communication_utils.h [deleted file]
otto_controller/Core/Src/main.cpp
utils/catkin_ws/src/joypad_bridge/scripts/serial_receiver.py

index 72fd203b595a8a268f4bef27aaa5194efc3ee3c4..bcf34bee1d8de912bb2ea19ed8320ac233b27bc3 100644 (file)
@@ -45,6 +45,7 @@
                                                                        <listOptionValue builtIn="false" value="../Core/Inc"/>
                                                                        <listOptionValue builtIn="false" value="../Drivers/STM32F7xx_HAL_Driver/Inc"/>
                                                                        <listOptionValue builtIn="false" value="../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy"/>
+                                                                       <listOptionValue builtIn="false" value="../Core/Inc/protobuf"/>
                                                                </option>
                                                                <option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="true" id="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.option.otherflags.978301265" name="Other flags" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.option.otherflags" useByScannerDiscovery="false" valueType="stringList"/>
                                                                <inputType id="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.input.c.1784720711" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.c.compiler.input.c"/>
@@ -58,6 +59,7 @@
                                                                        <listOptionValue builtIn="false" value="../Core/Inc"/>
                                                                        <listOptionValue builtIn="false" value="../Drivers/STM32F7xx_HAL_Driver/Inc"/>
                                                                        <listOptionValue builtIn="false" value="../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy"/>
+                                                                       <listOptionValue builtIn="false" value="../Core/Inc/protobuf"/>
                                                                </option>
                                                                <option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.cpp.compiler.option.definedsymbols.1826209638" name="Define symbols (-D)" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.cpp.compiler.option.definedsymbols" useByScannerDiscovery="false" valueType="definedSymbols">
                                                                        <listOptionValue builtIn="false" value="USE_HAL_DRIVER"/>
diff --git a/otto_controller/Core/Inc/communication_utils.h b/otto_controller/Core/Inc/communication_utils.h
deleted file mode 100644 (file)
index c2d4582..0000000
+++ /dev/null
@@ -1,37 +0,0 @@
-// __attribute__((packed)) -> no padding bytes
-typedef struct __attribute__((packed)) {
-  float angular_velocity;
-  float linear_velocity;
-  float delta_time;
-} odometry_msg;
-
-typedef struct __attribute__((packed)) {
-  float linear_velocity;
-  float angular_velocity;
-} velocity_msg;
-
-typedef struct __attribute__((packed)) {
-  float pid_select;
-  float pid_setpoint_fixed;
-  float pid_setpoint_lin;
-  float pid_setpoint_ang;
-  float pid_kp;
-  float pid_ki;
-  float pid_kd;
-} pid_setup_msg;
-
-typedef struct __attribute__((packed)) {
-  float velocity;
-//  float millis;
-} plot_msg;
-
-typedef struct __attribute__((packed)){
-  int left_ticks;
-  int right_ticks;
-} ticks_msg;
-
-typedef struct __attribute__((packed)){
-  float left_vel;
-  float right_vel;
-} wheel_msg;
-
index 8b2da4e416bed450367669ef78de022a0c678807..9037cd1d018f0114c0c31113fcf999e903425ecb 100644 (file)
 /* Private includes ----------------------------------------------------------*/\r
 /* USER CODE BEGIN Includes */\r
 \r
-#include "encoder.h"\r
-#include "odometry.h"\r
-#include "motor_controller.h"\r
-#include "pid.h"\r
-#include "communication_utils.h"\r
+#include "control/encoder.h"\r
+#include "control/odometry.h"\r
+#include "control/motor_controller.h"\r
+#include "control/pid.h"\r
 \r
-#include "pb_encode.h"\r
-#include "pb_decode.h"\r
-#include "otto_communication.pb.h"\r
+#include "protobuf/otto_communication.pb.h"\r
+#include "protobuf/pb_encode.h"\r
+#include "protobuf/pb_decode.h"\r
 \r
 /* USER CODE END Includes */\r
 \r
@@ -98,12 +97,6 @@ sleep2_Pin,
                            &htim4, TIM_CHANNEL_3);\r
 \r
 //Communication\r
-uint8_t *tx_buffer;\r
-uint8_t *rx_buffer;\r
-\r
-velocity_msg vel_msg;\r
-wheel_msg wheels_msg;\r
-\r
 int mode = 0;  //setup mode\r
 \r
 uint8_t proto_buffer_rx[50];\r
@@ -121,11 +114,6 @@ size_t status_msg_length;
 bool tx_status;\r
 float previous_tx_millis;\r
 \r
-//TEST variables\r
-long start_time;\r
-long end_time;\r
-int time_diff;\r
-\r
 /* USER CODE END PV */\r
 \r
 /* Private function prototypes -----------------------------------------------*/\r
@@ -197,11 +185,7 @@ int main(void)
   left_motor.coast();\r
   right_motor.coast();\r
 \r
-  tx_buffer = (uint8_t*) &wheels_msg;\r
-  rx_buffer = (uint8_t*) &vel_msg;\r
-\r
-  //proto stuff\r
-\r
+  //protobuffer messages init\r
   vel_cmd = VelocityCommand_init_zero;\r
   status_msg = StatusMessage_init_zero;\r
 \r
@@ -334,9 +318,6 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {
 }\r
 \r
 void HAL_UART_RxCpltCallback(UART_HandleTypeDef *UartHandle) {\r
-\r
-  start_time = HAL_GetTick();\r
-\r
 //  size_t buffer_size = sizeof(proto_buffer_rx);\r
 //  uint8_t buffer_copy[buffer_size];\r
 //  memcpy((void *) &buffer_copy, &proto_buffer_rx, buffer_size);\r
@@ -377,9 +358,6 @@ void HAL_UART_RxCpltCallback(UART_HandleTypeDef *UartHandle) {
 \r
   HAL_UART_Receive_DMA(&huart6, (uint8_t*) &proto_buffer_rx,\r
                        VelocityCommand_size);\r
-\r
-  end_time = HAL_GetTick();\r
-  time_diff = end_time - start_time;\r
 }\r
 \r
 void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) {\r
@@ -391,7 +369,6 @@ void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) {
       HAL_TIM_Base_Start_IT(&htim3);\r
 \r
     }\r
-\r
   }\r
 }\r
 /* USER CODE END 4 */\r
index 196f594e28d28765fdc7be921684ecb23420a9ea..c9e46f4a498de4065cdc26c7e54bc325d133e08b 100755 (executable)
@@ -47,14 +47,12 @@ def serial_receiver():
     encoded_buffer = otto_status.SerializeToString()
 
     status_length = len(encoded_buffer)
-    print (status_length)
 
     odom_values = numpy.array([0,0,0]) #x, y, th
     icc_x = 0;current_time = rospy.Time.now()
-
     icc_y = 0;
     radius = 0;
-
+    
     while (not rospy.is_shutdown()):
         ser.reset_input_buffer()
         encoded_buffer = ser.read(status_length)