]> git.leonardobizzoni.com Git - pioneer-stm32/commitdiff
remove throttle node, computer->st transmission works without it
authorFederica Di Lauro <federicadilauro1998@gmail.com>
Sun, 15 Mar 2020 11:14:28 +0000 (12:14 +0100)
committerFederica Di Lauro <federicadilauro1998@gmail.com>
Sun, 15 Mar 2020 11:14:28 +0000 (12:14 +0100)
otto_controller/Core/Src/main.cpp
otto_controller/otto_controller.ioc
utils/catkin_ws/launch/serial_bridge.launch
utils/catkin_ws/src/serial_bridge/scripts/serial_receiver.py
utils/catkin_ws/src/serial_bridge/scripts/serial_transmitter.py

index a5bdc7c4fd7b2dad130c5081720aa650440e193a..06adeceecef4b1ab7f720c11e855959649b5c8dc 100644 (file)
@@ -302,7 +302,9 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {
     float left_wheel = left_encoder.GetLinearVelocity();\r
     float right_wheel = right_encoder.GetLinearVelocity();\r
 \r
-    odom.FromWheelVelToOdom(left_wheel, right_wheel);\r
+//    odom.FromWheelVelToOdom(left_wheel, right_wheel);\r
+\r
+    odom.FromWheelVelToOdom(0.5, -0.5);\r
 \r
     status_msg.linear_velocity = odom.GetLinearVelocity();\r
     status_msg.angular_velocity = odom.GetAngularVelocity();\r
@@ -361,10 +363,10 @@ void HAL_UART_RxCpltCallback(UART_HandleTypeDef *UartHandle) {
   VelocityCommand_size);\r
 }\r
 \r
-void HAL_UART_ErrorCallback(UART_HandleTypeDef *UartHandle){\r
+void HAL_UART_ErrorCallback(UART_HandleTypeDef *UartHandle) {\r
   error++;\r
   HAL_UART_Receive_DMA(&huart6, (uint8_t*) &proto_buffer_rx,\r
-    VelocityCommand_size);\r
+  VelocityCommand_size);\r
 }\r
 \r
 void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) {\r
index dbdd3dbf885ecb47c014b5a59ecb35b3a1aeb252..c720e7893c8ac9e24ef07313f99e78d6922bdb0a 100644 (file)
@@ -166,7 +166,7 @@ PF15.Signal=GPIO_Output
 PG8.Mode=RTS_Only
 PG8.Signal=USART6_RTS
 PinOutPanel.RotationAngle=0
-ProjectManager.AskForMigrate=false
+ProjectManager.AskForMigrate=true
 ProjectManager.BackupPrevious=false
 ProjectManager.CompilerOptimize=6
 ProjectManager.ComputerToolchain=false
@@ -273,3 +273,4 @@ VP_TIM4_VS_ClockSourceINT.Signal=TIM4_VS_ClockSourceINT
 VP_TIM6_VS_ClockSourceINT.Mode=Enable_Timer
 VP_TIM6_VS_ClockSourceINT.Signal=TIM6_VS_ClockSourceINT
 board=custom
+isbadioc=false
index 2d00cb6e41bee986eb7f9e2d3f102773ac4d0cd0..a8bea99f0f416c820f57584f51af5b92ae1411cb 100644 (file)
@@ -3,10 +3,6 @@
   <node name="serial_transmitter" pkg="serial_bridge" type="serial_transmitter.py"/>
   <node name="serial_receiver" pkg="serial_bridge" type="serial_receiver.py"/>
   
-  <!-- Node used to slow down /cmd_vel transmission to 10Hz -->
-  <!-- <node name="cmd_vel_throttler" type="throttle" pkg="topic_tools" 
-        args="messages /cmd_vel 10000 /cmd_vel_throttled" /> -->
-  
   <!-- Serial port -->  
   <param name="serial_port" value="/dev/ttyUSB0"/>
   
index 0acc9f90906de828507a281f24c002610e2258c1..da14e7414b941dd6875488b07e111f6188ff22d1 100755 (executable)
@@ -12,8 +12,6 @@ import tf
 
 import numpy
 
-
-
 ser = serial.Serial(
         baudrate=9600,
         timeout = None,
@@ -35,7 +33,6 @@ def serial_receiver():
             time.sleep(2)
 
     rospy.loginfo(serial_port + ' opened')
-
     odom_pub = rospy.Publisher('/odom', Odometry, queue_size=10)
     odom_broadcaster = tf.TransformBroadcaster()
 
@@ -55,10 +52,9 @@ def serial_receiver():
     radius = 0
     current_time = rospy.Time.now()
     
+    ser.reset_input_buffer()
     while (not rospy.is_shutdown()):
-        ser.reset_input_buffer()
         encoded_buffer = ser.read(status_length)
-        
         try:
             otto_status.ParseFromString(encoded_buffer)
             rospy.logdebug(otto_status)
@@ -112,6 +108,5 @@ def serial_receiver():
             rospy.logerr("Decode Error")
             ser.reset_input_buffer()
 
-
 if __name__ == '__main__':
     serial_receiver()
index a1774c3744feff11e3b36f266873143c34f601ae..0f919a96c81532535c7ab8455fc8f876a12cdfe2 100755 (executable)
@@ -1,5 +1,6 @@
 #!/usr/bin/env python
 
+
 import rospy, serial
 import otto_communication_pb2
 from geometry_msgs.msg import Twist
@@ -8,6 +9,7 @@ from serial import SerialException
 ser = serial.Serial(
         baudrate=9600,
         parity=serial.PARITY_NONE,
+
         stopbits=serial.STOPBITS_ONE,
         bytesize=serial.EIGHTBITS,
         rtscts=True,
@@ -41,7 +43,7 @@ def listener():
     
     rospy.loginfo(serial_port + ' opened')
 
-    rospy.Subscriber('/cmd_vel_throttled', Twist, callback)
+    rospy.Subscriber('/cmd_vel', Twist, callback)
 
     rospy.spin()