From 1cce39fc9e2ccd9921fe9836f776e837f69c5671 Mon Sep 17 00:00:00 2001 From: Federica Di Lauro Date: Sun, 15 Mar 2020 12:14:28 +0100 Subject: [PATCH] remove throttle node, computer->st transmission works without it --- otto_controller/Core/Src/main.cpp | 8 +++++--- otto_controller/otto_controller.ioc | 3 ++- utils/catkin_ws/launch/serial_bridge.launch | 4 ---- .../src/serial_bridge/scripts/serial_receiver.py | 7 +------ .../src/serial_bridge/scripts/serial_transmitter.py | 4 +++- 5 files changed, 11 insertions(+), 15 deletions(-) diff --git a/otto_controller/Core/Src/main.cpp b/otto_controller/Core/Src/main.cpp index a5bdc7c..06adece 100644 --- a/otto_controller/Core/Src/main.cpp +++ b/otto_controller/Core/Src/main.cpp @@ -302,7 +302,9 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) { float left_wheel = left_encoder.GetLinearVelocity(); float right_wheel = right_encoder.GetLinearVelocity(); - odom.FromWheelVelToOdom(left_wheel, right_wheel); +// odom.FromWheelVelToOdom(left_wheel, right_wheel); + + odom.FromWheelVelToOdom(0.5, -0.5); status_msg.linear_velocity = odom.GetLinearVelocity(); status_msg.angular_velocity = odom.GetAngularVelocity(); @@ -361,10 +363,10 @@ void HAL_UART_RxCpltCallback(UART_HandleTypeDef *UartHandle) { VelocityCommand_size); } -void HAL_UART_ErrorCallback(UART_HandleTypeDef *UartHandle){ +void HAL_UART_ErrorCallback(UART_HandleTypeDef *UartHandle) { error++; HAL_UART_Receive_DMA(&huart6, (uint8_t*) &proto_buffer_rx, - VelocityCommand_size); + VelocityCommand_size); } void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) { diff --git a/otto_controller/otto_controller.ioc b/otto_controller/otto_controller.ioc index dbdd3db..c720e78 100644 --- a/otto_controller/otto_controller.ioc +++ b/otto_controller/otto_controller.ioc @@ -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 diff --git a/utils/catkin_ws/launch/serial_bridge.launch b/utils/catkin_ws/launch/serial_bridge.launch index 2d00cb6..a8bea99 100644 --- a/utils/catkin_ws/launch/serial_bridge.launch +++ b/utils/catkin_ws/launch/serial_bridge.launch @@ -3,10 +3,6 @@ - - - diff --git a/utils/catkin_ws/src/serial_bridge/scripts/serial_receiver.py b/utils/catkin_ws/src/serial_bridge/scripts/serial_receiver.py index 0acc9f9..da14e74 100755 --- a/utils/catkin_ws/src/serial_bridge/scripts/serial_receiver.py +++ b/utils/catkin_ws/src/serial_bridge/scripts/serial_receiver.py @@ -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() diff --git a/utils/catkin_ws/src/serial_bridge/scripts/serial_transmitter.py b/utils/catkin_ws/src/serial_bridge/scripts/serial_transmitter.py index a1774c3..0f919a9 100755 --- a/utils/catkin_ws/src/serial_bridge/scripts/serial_transmitter.py +++ b/utils/catkin_ws/src/serial_bridge/scripts/serial_transmitter.py @@ -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() -- 2.52.0